Dynamic Event (#632)

Posted by @mxgrey:

When rmf_task was originally designed, it was intended to allow users to specify custom task definitions, including custom phase types, and behaviors with many branches, like what is often seen in systems driven by behavior trees.

Ultimately it proved very difficult to implement such systems safely in a multi-threaded environment. It proved even more difficult to offer user-friendly APIs for introducing custom tasks and custom phases. As we started thinking about “next generation” aspirations, a decision was made to move away from the C+±based rmf_task framework and move towards a Rust-based general workflow library (bevy_impulse) to support the more complex behaviors that users need for dealing with tricky applications.

While bevy_impulse is making considerable progress, it is unlikely to be deployment-ready along with an end-to-end next generation Open-RMF framework before the end of the 2025 calendar year. At the same time, there may already be some deployments that have an urgent need to support more complex behaviors than what rmf_task currently offers out of the box, e.g. there may be a need for phases with conditional branching and explicit error handling.

I’d like to propose a new event type, which I’m tentatively calling a “Dynamic Event”. This event would work by running a ROS 2 action server that waits for event descriptions to be requested by a remote action client in the form of a JSON message that matches a supported event description schema, such as go_to_place, perform_action, sequence, or any others that can normally be used inside of a composed task.

The action messages would take the following form:

# request
uint32 event_type

# Default value for event_type, indicates that the message was default-initialized.
# This will immediately be rejected by the action server.
uint32 EVENT_TYPE_UNINITIALIZED=0

# Indicates that this request describes the next event for the phase to execute.
uint32 EVENT_TYPE_NEXT=1

# Cancel the currently active event. The id field must match the ID of the 
uint32 EVENT_TYPE_CANCEL=2

# Indicates that the dynamic events are finished. After this, no more event commands can 
# be sent until a new Dynamic Event begins.
uint32 EVENT_TYPE_FINISHED=3

# Used to specify the category of the event when event_type is EVENT_TYPE_NEXT.
# Otherwise this is unused.
string category

# Used to describe the event when event_type is EVENT_TYPE_NEXT.
# Otherwise this is unused.
string description

# When using EVENT_TYPE_NEXT, this will be the ID for the newly created event.
#
# When using EVENT_TYPE_CANCEL, this indicates the ID of the event that is supposed to
# be cancelled. If it does not match the currently active event ID, then the request will be
# rejected. If it does match, then the action response will be sent once the event has
# finished its cancellation.
uint64 id

---
# Response

# The last status of the action before it was finished
string status

# The ID of the event which has finished
uint64 id

---
# Feedback

# Current status of the action. This string will match one of the values in the "status" schema:
# https://github.com/open-rmf/rmf_api_msgs/rmf_api_msgs/schemas/task_state.json
string status

# The ID of the currently active event.
uint64 id

# Log messages that have occurred since the last feedback message. Matches the log_entry schema:
# https://github.com/open-rmf/rmf_api_msgs/blob/main/rmf_api_msgs/schemas/log_entry.json
rmf_fleet_msgs/LogEntry[] logs

Each robot in each fleet would have its own action channel with the name "rmf_dynamic_event/command/<fleet_name>/<robot_name>". The same action server will be used each time a dynamic event is active for a robot. If a dynamic event is not active, any action requests will be immediately rejected. If a dynamic event is currently executing a previous event action request, then any action requests to begin a new event will be immediately rejected. Only EVENT_TYPE_CANCEL requests can be sent while a prior event is being executed, and those requests must have their id field match the id of the ongoing event.

While no event is being executed, an EVENT_TYPE_FINISHED request can be sent to tell the dynamic event to stop waiting for new requests and end its execution. At that point, the task execution will proceed to the next event in the task description.

Schemas

To be included in a composed task description, we need to define an event description schema. I propose the following (depicted as an example, not as a schema definition):

{
    "category": "dynamic_event",
    "description": {
        "estimate": {
            "category": "sequence",
            "description": [
                {
                    "category": "go_to_place",
                    "description": "L1_lobby_A"
                },
                {
                    "category": "go_to_place",
                    "description": "L2_lobby_B"
                }
            ]
        }
    }
}

Since the actual event that will be run is determined at runtime, no information is needed in the description for executing the event. However, an estimate field is needed for the task planner to properly plan for the event. If the dynamic event involves travelling over large distances or performing long-running actions, then it’s important that the task planner can take that into account.

The estimate field should contain event information similar to the activity field in a composed task. This information will be used to generate the task model used by the planner. Ideally this estimate will describe the sequence of events that is most likely to occur (e.g. what should happen if no errors occur or all expectations are met). In some cases system integrators may choose to describe a best-case scenario or a worst-case scenario depending on which would be more beneficial for the overall deployment.

If no estimate field is provided then the dynamic event will have no effect on the task model.

Besides the estimate field, system integrators can add any additional fields into the description of the dynamic_event. The additional fields will not be used by the planner or for the task execution, but will be preserved. When the dynamic event begins, the entire description will be published to the "rmf_dynamic_event/description" in a rmf_fleet_msgs/DynamicEventDescription message:

# Name of the fleet of the robot beginning the dynamic event
string fleet

# Name of the robot beginning the dynamic event
string robot

# Full JSON description of the dynamic event, including the estimate field 
# and any custom fields put in by the task request
string description

There will also be a service for each robot to fetch the description of any ongoing dynamic event, at the service channel "rmf_dynamic_event/description/<fleet_name>/<robot_name>":

# Request

# ROS messages require at least one field
bool at_least_one_field

---
# Response

# True if a dynamic event is running for the robot, false otherwise.
# If false, all other fields will just be default-initialized.
bool running

# Current status of the action. This string will match one of the values in the "status" schema:
# https://github.com/open-rmf/rmf_api_msgs/rmf_api_msgs/schemas/task_state.json
string status

# Full JSON description of the dynamic event, including the estimate field 
# and any custom fields put in by the task request
string description

# The ID of the current event
uint64 id

Edited by @mxgrey at 2025-03-11T09:00:13Z

Posted by @TanJunKiat:

Hi Grey, thanks for starting this.

The initial proposal looks great and might be sufficient for us to implement our workflow.

I already can see it being used in our deployment. For example, using it to start and stop full control robots to allow interoperability with read-only (sometimes the deconfliction algorithm is not performing as predicted and/or closing lane might disrupt the planner), or using this in conjunction with lane closing to direct robots between two different lifts for lift selection.

A few questions I have:

  • Must the JSON task schema be predefined? Will it be more versatile if the action client request to contain the task schema? For example, having an external algorithm to determine which waypoint is the best or free for the robot to go to, before sending a JSON schema to the robot to ask it to go there.

  • How will this interact with the bidding system? Assuming the case above and the case where the JSON schema is fixed, must this new dispatch task give the robot name as an argument or will it go through the bidding system and get evaluated as if it is like a series of tasks with its respective cost? And while a robot is busy with the dynamic event task, does it still allocate a task into the queue?

  • How will the deconfliction behaviour be like in a scenario where a robot is waiting for the trigger to proceed with the next phase, with another robot coming along its path, assuming there is no alternate path? Will the behaviour be similar to having responsive wait enabled?

Posted by @mxgrey:

using it to start and stop full control robots to allow interoperability with read-only

For this I recommend using the interrupt_task_request message. That will pause whatever task the robot is running until you issue a matching resume_task_request message.

We could add a field to the interrupt_task_request schema which tells the robot to begin running the dynamic event server while the robot is interrupted. In the past the interruption request was used to allow vendor-specific teleoperation pipelines to run without conflicting with RMF, but if we make it an option to activate the dynamic event server while interrupted then you could have a pipeline that simply issues dynamic event commands to the robot while it’s interrupted.

Must the JSON task schema be predefined?

I’m not totally clear on which schema you’re referring to here.

  • The dispatch task request and robot task request schemas are used to issue new tasks into RMF
  • The compose task schema is used in the request field of dispatch task request or robot task request to describe the task that needs to be run
  • The dynamic event schema that I described in the original post could be put into the activity field for one or more phases of the compose task schema. It could also be added as an item in the activities field of an event sequence. The choice boils down to how much of the task is fixed (which helps the planner make better predictions) versus how much of the task needs to be dynamic.

Which of the above schemas are you concerned about being predefined?

For the dynamic event schema, the only part that’s predefined is the estimate field, but you are free to add any more fields to it that you want, and those fields will be preserved and sent out over the rmf_dynamic_event/description topic and the rmf_dynamic_event/description/<fleet_name>/<robot_name> service so that an external planner can know how the event should be configured.

How will this interact with the bidding system? Assuming the case above and the case where the JSON schema is fixed, must this new dispatch task give the robot name as an argument or will it go through the bidding system and get evaluated as if it is like a series of tasks with its respective cost?

Because of the estimate field it can interact with the bidding system just like any other task. The estimate will be used to construct the planning model for the event, so that combined with the models of any other phases/events in the task description will determine the overall cost of the task.

Because of this, different use cases may prefer that the estimate is a lower estimate of the actions that might be taken, or an upper estimate of the actions that might be taken, or an estimate of the most probable sequence of actions that might be taken. Ultimately it’s up to the system integrator to decide which makes the most sense for their use case.

And while a robot is busy with the dynamic event task, does it still allocate a task into the queue?

The dynamic event will work just like every other task. The dynamic event action server will only kick in when the robot is currently running a task and that task contains a phase or event that is a dynamic event, and the task reaches that point in its execution. Once you send the DynamicEvent.Request.event_type = EVENT_TYPE_FINISHED action request, the dynamic event will finish and the task will proceed to its next phase/event.

How will the deconfliction behaviour be like in a scenario where a robot is waiting for the trigger to proceed with the next phase, with another robot coming along its path

As always, it is best to only issue go_to_place commands to locations that are not in areas where traffic passes through. Any time that a robot ends its go_to_place in an area with traffic, the traffic planning will get messy, regardless of responsive wait or other mitigating strategies.

We could consider adding an idle_behavior field to the dynamic_event schema (alongside estimate) so users could do "idle_behavior": "responsive_wait" to get the responsive wait behavior, or "idle_behavior": "stubborn" which would have the robot broadcast its current location to the schedule and be a “stubborn negotiator”, meaning other robot are forced to reroute. The stubborn behavior is what’s recommended for teleoperated robots. Either way it will be much better to always end outside of traffic and to turn on the reservation system.

Posted by @TanJunKiat:

For this I recommend using the interrupt_task_request message. That will pause whatever task the robot is running until you issue a matching resume_task_request message.

We could add a field to the interrupt_task_request schema which tells the robot to begin running the dynamic event server while the robot is interrupted. In the past the interruption request was used to allow vendor-specific teleoperation pipelines to run without conflicting with RMF, but if we make it an option to activate the dynamic event server while interrupted then you could have a pipeline that simply issues dynamic event commands to the robot while it’s interrupted.

I agree that activating the dynamic event server while interrupted might be useful, being able to utilize the robot for a different task, and resuming the previous task once done.

Which of the above schemas are you concerned about being predefined?

What I understood of the dynamic event workflow is that the JSON that you defined in the original post is passed to the robot when the task is allocated. And upon triggering of an action client, the robot will move to the next task in the sequence’s description. Must this sequence be predefined?

We could consider adding an idle_behavior field to the dynamic_event schema (alongside estimate) so users could do “idle_behavior”: “responsive_wait” to get the responsive wait behavior, or “idle_behavior”: “stubborn” which would have the robot broadcast its current location to the schedule and be a “stubborn negotiator”, meaning other robot are forced to reroute. The stubborn behavior is what’s recommended for teleoperated robots. Either way it will be much better to always end outside of traffic and to turn on the reservation system.

I think this implementation would work. Manually sending a dynamic event go_to_place might not be the best because it makes the responsibility of deconfliction on the user, rather than on rmf.

Posted by @mxgrey:

And upon triggering of an action client, the robot will move to the next task in the sequence’s description. Must this sequence be predefined?

This is not correct. When you’re looking at the example description note that the sequence is inside of the estimate field. The information in that field is only used to generate the task estimation model. It does not get used to execute anything at all. Nothing will be executed until an action client issues a DynamicEvent::Request command.

I’ve updated the IDL for DynamicEvent::Request in a way that hopefully makes it more clear. Now the ROS request message has a string category field and a string description field which match the task_description__compose.activity schema. When you issue a DynamicEvent action request you will specify a category and description for the event that you want to be executed, and that will be executed regardless of whatever was originally in the estimate field and regardless of whatever else was put inside the original task description.

Your category and description can match any of the event_description__... schemas in rmf_fleet_adapter. Those are the event descriptions that rmf_fleet_adapter knows how to execute. Other than that there is no limit on what can be executed or in what order, except that they can only execute one at a time for a single robot.

Manually sending a dynamic event go_to_place might not be the best because it makes the responsibility of deconfliction on the user, rather than on rmf.

We may have a miscommunication here. I fully expect that go_to_place will be the most common dynamic event request that gets sent. Requesting a go_to_place dynamic event will still do all the normal traffic deconfliction that you would get by issuing a go_to_place task or by including a go_to_place phase inside of a task or a sequence.

But in all of those cases equally, it’s a bad idea to issue the go_to_place to a location that traffic is likely to pass through. That always carries a risk of being disruptive to the traffic.


Edited by @mxgrey at 2025-03-11T09:12:45Z

Posted by @TanJunKiat:

I’ve updated the IDL for DynamicEvent::Request in a way that hopefully makes it more clear.

Yea, thanks. I see what you meant now. The method seems sound and universal for different intentions.

We may have a miscommunication here. I fully expect that go_to_place will be the most common dynamic event request that gets sent. Requesting a go_to_place dynamic event will still do all the normal traffic deconfliction that you would get by issuing a go_to_place task or by including a go_to_place phase inside of a task or a sequence.

oh yea, understood what you meant.

Posted by @TanJunKiat:

@mxgrey

In terms of implementation, is there anything on my side that I can help with?

We can co-implement this feature and of course, we can test it here at our lab to check the on physical hardware.

Posted by @TanJunKiat:

Hi @mxgrey

We tried to run the new dynamic_event task

Here is the script that we used for testing

#!/usr/bin/env python3

# Copyright 2025 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
"""Dynamic Event."""

import argparse
import asyncio
import json
import math
import sys
import uuid

import rclpy
from rclpy.node import Node
from rclpy.parameter import Parameter
from rclpy.qos import QoSDurabilityPolicy as Durability
from rclpy.qos import QoSHistoryPolicy as History
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy as Reliability

from rmf_task_msgs.msg import ApiRequest
from rmf_task_msgs.msg import ApiResponse

###############################################################################


class TaskRequester(Node):
    """Task requester."""

    def __init__(self, argv=sys.argv):
        """Initialize a task requester."""
        super().__init__('task_requester')
        parser = argparse.ArgumentParser()
        parser.add_argument('-F', '--fleet', type=str, help='Fleet name')
        parser.add_argument('-R', '--robot', type=str, help='Robot name')
        parser.add_argument(
            '-p',
            '--place',
            required=True,
            type=str,
            help='Place to go to',
            nargs='+',
        )
        parser.add_argument(
            '--use_sim_time',
            action='store_true',
            help='Use sim time, default: false',
        )
        parser.add_argument(
            '--requester',
            help='Entity that is requesting this task',
            type=str,
            default='rmf_demos_tasks'
        )

        self.args = parser.parse_args(argv[1:])
        self.response = asyncio.Future()

        transient_qos = QoSProfile(
            history=History.KEEP_LAST,
            depth=1,
            reliability=Reliability.RELIABLE,
            durability=Durability.TRANSIENT_LOCAL,
        )

        self.pub = self.create_publisher(
            ApiRequest, 'task_api_requests', transient_qos
        )

        # enable ros sim time
        if self.args.use_sim_time:
            self.get_logger().info('Using Sim Time')
            param = Parameter('use_sim_time', Parameter.Type.BOOL, True)
            self.set_parameters([param])

        # Construct task
        msg = ApiRequest()
        msg.request_id = 'direct_' + str(uuid.uuid4())
        payload = {}

        if self.args.robot and self.args.fleet:
            self.get_logger().info("Using 'robot_task_request'")
            payload['type'] = 'robot_task_request'
            payload['robot'] = self.args.robot
            payload['fleet'] = self.args.fleet
        else:
            self.get_logger().info("Using 'dispatch_task_request'")
            payload['type'] = 'dispatch_task_request'

        # Set task request start time
        now = self.get_clock().now().to_msg()
        start_time = now.sec * 1000 + round(now.nanosec / 10**6)
        # todo(YV): Fill priority after schema is added

        # Define task request description
        one_of = []
        for place in self.args.place:
            place_json = {'waypoint': place}
            one_of.append(place_json)

        go_to_description = {'one_of': one_of}

        dynamic_event_activity = {
            'category': 'dynamic_event',
            'description': go_to_description,
        }

        rmf_task_request = {
            'category': 'compose',
            'description': {
                'category': 'dynamic_event',
                'phases': [{'activity': dynamic_event_activity}],
            },
            'unix_millis_request_time': start_time,
            'unix_millis_earliest_start_time': start_time,
            'requester': self.args.requester,
        }

        if self.args.fleet:
            rmf_task_request['fleet_name'] = self.args.fleet

        payload['request'] = rmf_task_request

        msg.json_msg = json.dumps(payload)

        def receive_response(response_msg: ApiResponse):
            if response_msg.request_id == msg.request_id:
                self.response.set_result(json.loads(response_msg.json_msg))

        self.sub = self.create_subscription(
            ApiResponse, 'task_api_responses', receive_response, 10
        )

        print(f'Json msg payload: \n{json.dumps(payload, indent=2)}')

        self.pub.publish(msg)


###############################################################################


def main(argv=sys.argv):
    """Go to place."""
    rclpy.init(args=sys.argv)
    args_without_ros = rclpy.utilities.remove_ros_args(sys.argv)

    task_requester = TaskRequester(args_without_ros)
    rclpy.spin_until_future_complete(
        task_requester, task_requester.response, timeout_sec=5.0
    )
    if task_requester.response.done():
        print(f'Got response: \n{task_requester.response.result()}')
    else:
        print('Did not get a response')
    rclpy.shutdown()


if __name__ == '__main__':
    main(sys.argv)

We see that the task was dispatched to one of the robots and a task ID is given.

After triggering the server with an action client

ros2 action send_goal /rmf/dynamic_event/command/tinyRobot/tinyRobot1 rmf_task_msgs/action/DynamicEvent "{event_type: 1, category: 'go_to_place', description: '{\"waypoint\": \"patrol_A1\"}', dynamic_event_seq: 1}"

We encountered this error

[fleet_adapter-16] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
[fleet_adapter-16]   what():  goal_handle attempted invalid transition from state EXECUTING with event EXECUTE, at ./src/rcl_action/goal_handle.c:95
[fleet_adapter-16] Fatal Python error: Aborted
[fleet_adapter-16] 
[fleet_adapter-16] Thread 0x0000761eaaffd6c0 (most recent call first):
[fleet_adapter-16]   File "/usr/lib/python3.12/concurrent/futures/thread.py", line 89 in _worker
[fleet_adapter-16]   File "/usr/lib/python3.12/threading.py", line 1010 in run
[fleet_adapter-16]   File "/usr/lib/python3.12/threading.py", line 1073 in _bootstrap_inner
[fleet_adapter-16]   File "/usr/lib/python3.12/threading.py", line 1030 in _bootstrap

We suspect is the action server failed to transit from handle_goal to handle_accepted.

Any hints on what the issue might be?

Posted by @mxgrey:

Thanks for getting started on the testing.

Could you open a PR for rmf_demos that adds this script to rmf_demos_tasks? That way I can clone it to test it on my end and we can do the debugging collaboratively.

Posted by @mxgrey:

Based on the error message I suspect rmf_fleet_adapter is accidentally double-triggering handle->execute(). One possibility is rclcpp_action might automatically trigger the ->execute() mode after the action server indicates that the goal was accepted, but I’m not sure, so I’ll have to toy around with it.

It looks like the example code never shows ->execute() being explicitly triggered, so I suspect this is the case.

Posted by @TanJunKiat:

Thanks for getting started on the testing.

Could you open a PR for rmf_demos that adds this script to rmf_demos_tasks? That way I can clone it to test it on my end and we can do the debugging collaboratively.

Please refer to Dynamic events by TanJunKiat · Pull Request #280 · open-rmf/rmf_demos · GitHub

Posted by @TanJunKiat:

Based on the error message I suspect rmf_fleet_adapter is accidentally double-triggering handle->execute(). One possibility is rclcpp_action might automatically trigger the ->execute() mode after the action server indicates that the goal was accepted, but I’m not sure, so I’ll have to toy around with it.

It looks like the example code never shows ->execute() being explicitly triggered, so I suspect this is the case.

Our engineer found that commenting out this line made it work.

For your reference.


Edited by @TanJunKiat at 2025-03-21T14:51:42Z

Posted by @mxgrey:

Our engineer found that commenting out this line made it work.

That’s what I suspected, thanks for verifying that. The PR has been updated to remove that line.

Let me know if you come across any other issues.

Posted by @asrafhamid:

Hi @mxgrey,

Thank you for the opportunity to test this new Dynamic Event feature. After conducting preliminary testing, I’ve compiled the following list of issues for your review:

Issue ID Topic Issue Possible Cause Severity Status Temp Fix Notes
ISSUE-01 Dynamic Event Goal request For NEXT event request, action server accepts goal but fleet adapter crashes. Error in goal accepting
double-triggering handle execution
major FIXED comment out handle->execute(); There are other handle->execute lines in handle accepting. Wonder if they should be removed as well
ISSUE-02 Dynamic Event Goal request For CANCEL event request, fail to process request Mishandle in goal accepting
Falls into if statement for expired callbacks OR dynamic goal not expired
Gets aborted: execution failure(“race condition”)
major TO TEST Ignore if statement if event_type is CANCEL
ISSUE-03 Dynamic Event Goal request For CANCEL and FINISH event request, action server rejects goal if category and description fields omitted Mishandle in goal handling
Falls into if statement for invalid category and description
Goals gets rejected
major TO TEST Ignore if statement if event_type is CANCEL or FINISH
ISSUE-04 Dynamic Event Goal request When robot is moving to location, a CANCEL request gets accepted but the robot only stops at the next waypoint in its path instead of stopping immediately major NON-ISSUE
ISSUE-05 Dynamic Event RMF task RMF Task cannot be cancelled when dynamic event is active minor/non (possibly intended behavior) TO TEST
ISSUE-06 Dynamic Event service The rmf_dynamic_event/description/<fleet_name>/<robot_name> service is not available minor NON-ISSUE

Edited by @asrafhamid at 2025-04-04T03:57:13Z

Posted by @mxgrey:

Thanks for the report.

If your team can update Dynamic events by TanJunKiat · Pull Request #280 · open-rmf/rmf_demos · GitHub with a script to help recreate these situations, I’ll be happy to debug these issues.

Posted by @mxgrey:

I’ve started looking over the items that I can reasonably debug without reproducing the problem.

  • ISSUE-02 should be addressed by c1dd343
  • ISSUE-03 should be addressed by afff68d

Posted by @mxgrey:

A few more updates:

  • ISSUE-04: As discussed offline, we’re going to treat this as the intended behavior for now
  • ISSUE-05: The cancellation was probably working already, but 069c3a2 should now fix the status updates
  • ISSUE-06: The proposed service has been replaced with two transient local topics:
    • rmf/dynamic_event/begin
    • rmf/dynamic_event/begin/<fleet_name>/<robot_name>

The only remaining issue, not listed, is to add a parameter for a “stubbornness period” after an event is complete.

Posted by @asrafhamid:

Some updates on fixes:

  • ISSUE-2 till ISSUE-4: tested and working

  • ISSUE-5: when rmf task (with dynamic event) is on standby, the status update correctly shows cancelled but when rmf task is underway (event is running), dashboard updates to standby. Is an update/visual issue as robot can be seen in idle behaviour and is still able to accept new rmf task request

Posted by @mxgrey:

I’m not sure why ISSUE-5 still isn’t working. Unfortunately I don’t think I’ll have much time this week to debug, but maybe you can help out.

Whenever the child event has a status update:

  • this line should copy the status of the child event into the main dynamic event,
  • this line should get triggered, and then
  • this line should tell the parent of the dynamic event that a status update needs to be transmitted.

If you can put some debug printouts around those code locations and figure out what is getting blocked, then that could help me identify the cause of the problem.


Edited by @mxgrey at 2025-04-07T09:24:41Z

Posted by @asrafhamid:

I’m not sure why ISSUE-5 still isn’t working. Unfortunately I don’t think I’ll have much time this week to debug, but maybe you can help out.

Whenever the child event has a status update:

  • this line should copy the status of the child event into the main dynamic event,
  • this line should get triggered, and then
  • this line should tell the parent of the dynamic event that a status update needs to be transmitted.

If you can put some debug printouts around those code locations and figure out what is getting blocked, then that could help me identify the cause of the problem.

At line if dynamic event is cancelled, I suggest adding two lines to explicitly transition the status to Canceled.

Here’s the updated code snippet:

if (me->_cancelled)
{
  me->_state->update_status(rmf_task::Event::Status::Canceled);
  me->_publish_update();
  me->_finished();
}

This ensures that when the dynamic event is canceled, the status transitions correctly from UnderwayStandbyCanceled. Without this explicit update, the status would remain stuck at Standby, causing the task to appear incomplete.