ROS2 Actions publish status messages that get exponentially more expensive

asked 2022-09-21 08:22:56 -0500

CraigH100 gravatar image

I am creating a graphical user interface with PySide6 for my ROS2 Application.

To test it, I am using the GUI to send goals to the examples_rclpy_minimal_action_server server_single_goal server.

In my GUI plumbing, there is a class that wraps the ROS2 ClientGoalHandle called QActionGoal(QObject). This QActionGoal has a property called status and status_str that can be used to get the int and string versions of the status enum. In order for QML to know when to redraw controls that use status and status_str, a signal needs to be emitted. Unfortunately, ClientGoalHandle does not have a on_status_changed_callback, so I have had to subscribe to the hidden topic: See code below:

class QActionGoal(QObject):
    def __init__(self):
        super().__init__()
        self.__handle: Optional[ClientGoalHandle] = None

    def set_handle(self, handle: ClientGoalHandle):
        self.__handle = handle
        cli: ActionClient = self.__handle._action_client
        node: Node = cli._node
        topic_name = cli._action_name + '/_action/status'
        node.create_subscription(GoalStatusArray, topic_name, self.__status_callback, 1)
        retry = 0
        while node.count_publishers(topic_name) == 0:
            if retry > 10:
                raise Exception(f'publisher for {topic_name} not ready')
            retry += 1
            time.sleep(0.1)
        get_logger('action_goal').info(f'subscriber for {topic_name} ready') #TODO change to debug

    def get_status(self) -> int:
        if self.__handle is None:
            return 0
        return self.__handle.status

    def get_status_str(self) -> str:
        return GOAL_STATUS.ENUM(self.get_status()).name

    def __status_callback(self, msg: GoalStatusArray):
        #TODO change to debug
        get_logger('action_goal').info(f'status callback: {[s.status for s in msg.status_list]}')
        current_status: GoalStatus = msg.status_list[-1]
        self.status_changed.emit(current_status.status)

    status_changed = Signal(int)
    status = Property(int, fget=get_status, notify=status_changed)
    status_str = Property(str, fget=get_status_str, notify=status_changed)

The bit to pay attention to is the:

get_logger('action_goal').info(f'status callback: {[s.status for s in msg.status_list]}') in the subscription callback.

When sending the first goal, this prints (as expected):

[INFO action_goal] status callback: [2]
[INFO action_goal] status callback: [4]

Because the goal status first changes to executing, and then to succeeded. But the next time a goal is sent, it prints:

[INFO action_goal] status callback: [4, 2]
[INFO action_goal] status callback: [4, 2]
[INFO action_goal] status callback: [4, 4]
[INFO action_goal] status callback: [4, 4]

4 Messages instead of two, and each of length 2. Why is it both republishing old statuses, and including the history of the status in each message?

This grows exponentially worse The full log after a few action calls is:

[INFO qt_node] Goal accepted for action /fibonacci
[INFO action_goal] subscriber for /fibonacci/_action/status ready
[INFO action_goal] status callback: [2]
[INFO action_goal] status callback: [4]
[INFO qt_node] Calling with {order: 5}
[INFO qt_node] Goal accepted for action /fibonacci
[INFO action_goal] subscriber for /fibonacci/_action/status ready
[INFO action_goal] status callback: [4, 2]
[INFO action_goal] status callback: [4, 2]
[INFO action_goal] status callback: [4, 4]
[INFO action_goal] status callback: [4, 4]
[INFO qt_node] Calling with {order: 5}
[INFO qt_node] Goal accepted for action /fibonacci
[INFO action_goal] subscriber for /fibonacci/_action/status ready
[INFO action_goal] status callback: [4, 4, 2]
[INFO action_goal] status callback: [4, 4, 2 ...
(more)
edit retag flag offensive close merge delete

Comments

Not an answer, but whenever I read "ROS" and "QML" or 'HMI" in a question, I immediately think of StefanFabian/qml_ros2_plugin or the ROS 1 version.

If you can't use that, it might perhaps at least provide you with some inspiration/insight.

As to:

Unfortunately, ClientGoalHandle does not have a on_status_changed_callback, so I have had to subscribe to the hidden topic

I'm confused: does action_tutorials/action_tutorials_py/action_tutorials_py/fibonacci_action_client.py now show how to receive feedback from an active action goal in a client?

gvdhoorn gravatar image gvdhoorn  ( 2022-09-22 02:42:12 -0500 )edit

"does ... not show how to receive feedback from an active action goal in a client?"

Unfortunately not. It has a method to get the feedback, but not the goal status.

https://github.com/ros2/demos/blob/40...

"StefanFabian/qml_ros2_plugin"

I looked into this, and it does not quite suit my needs.

As for taking inspiration from it, Stefan updates the goal status during the feedback callback. This isn't ideal, I want to know when the action is executing, cancelling, etc, as soon as possible. Waiting for a feedback message (which might not come) is not suitable for me.

https://github.com/StefanFabian/qml_r...

CraigH100 gravatar image CraigH100  ( 2022-09-22 18:20:49 -0500 )edit

Afaik, the feedback topic/channel is not meant to update you on the status of the goal execution. It provides you with the status of the goal while it's executing.

The goal status is communicated using the goal response callback (ie: this part). The feedback itself is then passed to your client using the feedback callback.

Afaik, it should not be necessary to subscribe to hidden topics. If you find you absolutely must, either the design of the actionlib client APIs needs updating (in which case I'd suggest to open an issue), or your code isn't using it correctly (by which I mean: there should be other / intended ways to achieve what you want).

gvdhoorn gravatar image gvdhoorn  ( 2022-09-23 02:15:24 -0500 )edit

@gvdhoorn Yeah the feedback callback is called with the feedback message, not the status. The ros2 qml plugin must have chosen to use it for that because there's no other way.

Unfortunately, the goal response callback is only called once when accepted or rejected. It's not called every time the status changes, which is a shame, because it would be really useful on the client side to monitor the goal handle moving through the state machine: accepted -> executing -> cancelled etc.

Currently the only way to do this is through the hidden topic that publishes this info.

Which is perhaps why the (possible) bug mentioned in the question exists. Because hardly anyone has used action statuses thoroughly.

I could open an issue on github.

I think there are two seperate issues though. One is that the Action Client is missing a way to be notified of action ...(more)

CraigH100 gravatar image CraigH100  ( 2022-09-25 09:15:15 -0500 )edit

If you believe something isn't as it should be, I'd suggest to open an issue.

If you do, please comment here with a link to it, so we keep things connected.

gvdhoorn gravatar image gvdhoorn  ( 2022-09-26 03:59:04 -0500 )edit

Did you open an issue for this @CraigH100?

gvdhoorn gravatar image gvdhoorn  ( 2022-09-30 03:28:09 -0500 )edit

Curious the status of this. Did an issue get filed? Please link here. I've been looking for example of proper use of status with ActionClient. Is the best practice to subscribe to the hidden topic?

dcconner gravatar image dcconner  ( 2022-10-17 20:15:59 -0500 )edit

I don't know whether it solves anything for what you observed specifically @CraigH100, but #q411394 seemed like it described a related issue, and ros2/rclpy#1070 is intended to resolve it.

Could be related.

gvdhoorn gravatar image gvdhoorn  ( 2023-01-15 06:39:49 -0500 )edit