Suboptimal lane sharing between multiple robots (#261)

Posted by @tonydangct:

Hi, I have a setup with two robots. The environment is one very long hallway, consisting of two unidirectional lanes (see pic for clarification)

I’m currently on the galactic-devel branch for most of the rmf project. The behavior I observe for my case seems very inefficient: e.g. when two delivery tasks are assigned to the two robots and the robots need to go along the same lane, the second robot pauses at the start of the lane until the first robot leaves that specific lane. This seems very time inefficient, especially because the lanes are quite long.

Adding intermediate waypoints to this lane, solves this issue somewhat, but still not in an optimal way… In this case, the second robot continuously receives paths along this lane with only 1 waypoint. So whenever it reaches the waypoint, it receives a new path to the next waypoint on this lane. This causes the robot to constantly start and stop at every single waypoint, which is very energy inefficient.

Any suggestions on how I can deal with this? Thanks in advance.

Chosen answer

Answer chosen by @tonydangct at 2022-10-28T09:21:41Z.
Answered by @mxgrey:

There’s a complex relationship between how nav graphs are constructed and what kind of traffic behavior you’ll end up with, especially in extreme cases like this, with very very long lanes. In the current implementation of RMF, each lane in the nav graph represents an indivisible unit of action that RMF is able to command to a robot, so an extremely long lane represents one extremely long unit of action. That kind of abnormally long action unit can cause undesirable outcomes like what you’re describing. We intend to make the planner less sensitive to nav graph topology in future versions of RMF, but in the mean time it does take some effort on the part of system integrators to be mindful of how the nav graph will effect traffic decisions.

The screen shot and description that you’ve provided doesn’t really paint a clear enough picture for me to think of concrete advice on how to improve the behavior here. If you’re able to provide map packages and launch files that let me recreate the problematic scenario on my own machine then I should be able to offer better guidance.

One possible factor here is that the current baked-in settings of the negotiation system are focused more on resolving conflicts quickly rather than resolving them optimally. I’ve been thinking about giving users the ability to tweak parameters for that, but so far our test cases have suggested that the quickly-found solutions are almost always the optimal solutions anyway. If this is an edge case where that trend no longer holds then that may provide the motivation I need to make the negotiation behavior configurable.

Posted by @mxgrey:

There’s a complex relationship between how nav graphs are constructed and what kind of traffic behavior you’ll end up with, especially in extreme cases like this, with very very long lanes. In the current implementation of RMF, each lane in the nav graph represents an indivisible unit of action that RMF is able to command to a robot, so an extremely long lane represents one extremely long unit of action. That kind of abnormally long action unit can cause undesirable outcomes like what you’re describing. We intend to make the planner less sensitive to nav graph topology in future versions of RMF, but in the mean time it does take some effort on the part of system integrators to be mindful of how the nav graph will effect traffic decisions.

The screen shot and description that you’ve provided doesn’t really paint a clear enough picture for me to think of concrete advice on how to improve the behavior here. If you’re able to provide map packages and launch files that let me recreate the problematic scenario on my own machine then I should be able to offer better guidance.

One possible factor here is that the current baked-in settings of the negotiation system are focused more on resolving conflicts quickly rather than resolving them optimally. I’ve been thinking about giving users the ability to tweak parameters for that, but so far our test cases have suggested that the quickly-found solutions are almost always the optimal solutions anyway. If this is an edge case where that trend no longer holds then that may provide the motivation I need to make the negotiation behavior configurable.


Edited by @mxgrey at 2022-10-27T09:18:18Z


This is the chosen answer.

Posted by @mxgrey:

After thinking more about your text description I think I understand the problem a bit better, and it’s not related to negotiation as I originally assumed but rather conflict detection and traffic dependency.

Since the robots are moving in the same direction down the lanes there isn’t really a “traffic conflict”, but there is a “traffic dependency”: the second robot should not enter the next lane segment until the first one has cleared it.

In the current design of the RobotCommandHandle , robots are only commanded to follow a path up to the point where the path segment is known to not conflict with any other robot’s itinerary. The next path segment will be provided when the robot declares that it has reached the end of the path segment that it has provided.

That design choice was made to mitigate the risk that system integrators would have errors in their integration where their robot goes too far down the path and into a conflict. Unfortunately it means that a straightforward implementation of a fleet adapter will have the robot pause at every segment of a long lane in this situation.

One option to smooth this out would be to add a “lookahead” section to the follow_new_path API that lets the system integrator check whether

  1. they’re expected to continue along a straight line after reaching the next waypoint, and
  2. whether it is safe to do so.
    If both are true, then the system integrator can ask for the next path segment command to be issued.

Another option might be to bury that logic internally in rmf_fleet_adapter so that if the system integrator reports that the robot is approaching the final waypoint and the fleet adapter knows the robot can continue on without conflicts, then rmf_fleet_adapter can preemptively issue a new follow_new_path command to keep the robot moving. I’m a little worried this approach could be surprising/unintuitive for users, but it would be the most straightforward way to get the desired behavior without breaking API+ABI.

Posted by @eliasdc:

Can the “traffic dependency” and/or “traffic conflic” features be disabled? If for example someone has a robot which checks it surroundings itself and will never hit an other robot.

Posted by @mxgrey:

Generally I wouldn’t recommend discarding the traffic negotiation system because the sensing and navigation of an individual robot is generally not sufficient to gracefully resolve traffic conflicts. Even if the robots do not collide, there is a significant risk they could get themselves into deadlocks (e.g. two robots trying to get through a narrow passage like a doorway in opposite directions) which they won’t be able to resolve without something like the traffic negotiation system.

That being said, there may be special cases where there’s no risk of conflicts, like if the robots always move along a predefined one-way loop with no intersections. I’d be curious to know what subset of features of RMF you consider to be required/valuable for your use case if traffic negotiation is not needed. That might help me recommend an integration strategy for you.

But whether or not your use case needs traffic negotiation, this is certainly an undesirable behavior that we should improve in RMF. I think the second option makes the most sense since it would keep the API+ABI stable while making the behavior of the robots more intuitive, even if the event flow of the API might feel a bit odd.

Posted by @zhangyuran-gg:

In the case of multiple robots passing through long lanes,due to “traffic dependency”,there may be a distance of one or two lane segments between robots,but in my simulation,robots still maintain a very long distance between each other.Is this related to the robot_path_requests received by the robots.I noticed that the first robot on this long road only received one robot_path_requests and the request contains the points at the ends of the road,while the middle robot received robot_path_requests for each small lane segment.I want to know why the first robot received robot_path_requests that only contained two points,and where is the code for this algorithm?and I want the robots to maintain a shorter spacing, how should I adjust it?
I’m sorry to bother you,if possible, I would be happy to share my files with you via email.

Posted by @mxgrey:

The source code for everything related to planning is here, but it’s a lot to digest.

The simplest explanation I can offer is that ordinarily a long straight stretch like this will be simplified to one command by the planner whenever possible, i.e. whenever there are no obstacles to watch out for. That’s what you see happen for the first robot.

For the second robot there’s a risk that it could run into the first robot if the first robot gets delayed. To prevent that, we put in traffic dependencies that hold the second robot back until the first robot is no longer a risk.

As for why the second robot is waiting so long, there are two possible reasons:

  1. The traffic dependency system is something we added on top of a few years of pre-existing planning code, and that planning code was not originally designed to detect this type of conflict, so it’s not always going to break down the long path in the most fine grained way.
  2. I recently discovered a bug in the schedule node that causes a robot’s progress to not always be reported as quickly as it should. That bug is fixed in this PR which was just merged into main. If you pull the latest main branch you’ll get the fix.

The issue you’re having may be caused by one or both of those issues. If it’s (2) then it should be fixed now. If the problem is (1) then it will only be fixed when the next generation planning is available for RMF. For the next generation planning I’ll be rewriting the planner and traffic dependency system to deal with continuous linear dependencies like this one.