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