Posted by @rocker12121:
I want to make a custom rmf package that is very lightweight and only cares about traffic conflict detection and scheduling. Can i just use the rmf_traffic repository/package for that? What is the most appropriate way to do that?
Basically I want to use the core RMF functionality of traffic management in a distributed way.
Also, is there a way to run rmf_traffic_schedule node separately on each robot? if yes, how can I do that? Please guide.
Posted by @mxgrey:
What is the most appropriate way to do that?
What you’re describing is the purpose behind rmf_traffic_ros2
which gets used internally by rmf_fleet_adapter
.
In theory rmf_traffic_ros2
was meant to be used the way you’re describing. In practice it’s somewhat difficult to tie everything together because async programming in C++ is sort of inherently difficult. We wrap up the implementation of all the async planning and negotiation into rmf_fleet_adapter
, exposing a much simpler API to integrate robots against.
I have some words of caution about building something directly against rmf_traffic_ros2
at this point in time:
- The async programming will be difficult and error prone (see the complexity of
rmf_fleet_adapter
’s implementation for reference).
- In the next generation we’re replacing the functionality of
rmf_traffic_ros2
with mapf
and bevy_impulse
. We will be making a shim so that the rmf_fleet_adapter
API can be used with these new libraries underneath, but we will not be making a shim for rmf_traffic_ros2
because its API doesn’t align with the new capabilities that we’ll be introducing in the next generation.
- The next generation libraries will be much easier to use for pure traffic scheduling because they are designed to be far more modular.
Overall, what you want is something that you’ll see better support for in our forthcoming work. You could use what’s already available today, but it’s likely to be deprecated by the time you finish getting it to work.
If you can elaborate on your use case and development timeline maybe I can give more guidance on which path makes more sense.
Posted by @rocker12121:
Thank you for quick response.
Actually i want to run a scenario with around 10 robots in a environment. I have configured the environment.
As openrmf seems purely centralized where everything from task allocation to traffic conflict detection and management is managed via centralized server and fleet adapter. I want to do something that makes a system distributed whether by running separate instances of traffic schedule node or any other possible way.
My use case is simply a more distributed system where each robot has its enough knowledge. and observe the behaviour of robots in case of connectivity lost.
Timeline is very short but there is no specific deadline.
Posted by @mxgrey:
As openrmf seems purely centralized
Looks can be deceiving. Open-RMF is decentralized first and foremost with the option to centralize as it suits you.
I want to do something that makes a system distributed whether by running separate instances of traffic schedule node
You’ll always want to have just one instance of the traffic schedule node because that’s like a shared database that gathers information about what all the different mobile robots intend to do and checks for conflicts between them.
To allow a node to read and write to the traffic schedule there are the following pieces you’ll need to handle:
Create a Traffic Participant
During setup:
While running:
Generate plans
During setup:
While running:
- Get a view of the current schedule
- Create a route validator using the view from the previous step
- Create planner options using the validator from the previous step
- Generate a plan from the robot’s start location to its destination, using the options from the previous step
- Use
get_itinerary
from the planner result and pass it along to the participant that you created during the Create a Traffic Participant
section
Negotiate
During setup:
While running:
- The callback for your negotiator must update the schedule and then execute the new plan that gets approved during the negotiation process.
Posted by @mxgrey:
Everything that I said above skips over a lot of the event-driven aspects of traffic management, such as waiting for doors, waiting for lifts, or waiting for other traffic participants to move out of the way of your robot. Without implementing all of this, your overall traffic system will behave very poorly.
All of that is implemented in rmf_fleet_adapter
in a way that saves you from even needing to think about it.
My recommendation would be to not use any of the rmf_traffic_ros2
capabilities directly, but instead integrate your robot against either rmf_fleet_adapter
or use free_fleet
. Either way you can choose to have a single fleet adapter per robot that runs on the robot itself or you could have a single fleet adapter that runs on a central server and then run the free_fleet
client on each robot individually.
While running normal fleet adapters you can just choose to limit the tasks to go_to_place
tasks using robot task requests, and use your own task management system to generate those tasks.
This would spare you from a lot of difficult work and also make it possible for you to migrate your system to the next generation when it becomes available.
Edited by @mxgrey at 2024-12-23T11:03:52Z
Posted by @rocker12121:
Got it.
One more thing.. Is there any way I can check the behavior of the robot when it loses connectivity during the mission?
Posted by @rocker12121:
What happens when a robot decomissions in the middle of a task and the idle behavior is true. And what is the best way to test it?
Posted by @mxgrey:
Is there any way I can check the behavior of the robot when it loses connectivity during the mission?
I may need you to elaborate on this question. I’m not sure which of the following you are asking:
- “What is the behavior when the robot loses its network connection?”
- “What API can I use to detect that the robot has lost its network connection?”
For (1) it will depend on how the fleet adapter for your particular robot platform is implemented, but in most cases the robot will continue carrying out the last command sent to it from RMF and then wait for its next instructions. From the RMF side, RMF will wait to issue the next command (s) until it has positive confirmation that the robot has reconnected and finished its last command. This may also mean that other robots who did not lose their connection will be delayed if they need to wait until the disconnected robot has finished its last command.
This situation happens very frequently with lifts since most robots will completely lose their network connection while they are inside a lift, so Open-RMF is designed to handle this gracefully.
For (2) there is no Open-RMF API for detecting whether a robot has lost its network connection since different robots have very different means for determining this.
Posted by @mxgrey:
What happens when a robot decomissions in the middle of a task and the idle behavior is true.
Decommissioning never affects an ongoing task. Ongoing tasks can only end by successfully finishing or by sending a cancel_task_request
.
Posted by @mxgrey:
You can test the decommissioning behavior by running a demo and using the api_request
script to send a commission request to a robot while it’s performing a task.