<> == Documentation == The MRRP uses a prioritized planning approach to find the robots routes. Additionally, there are a Priority and a Speed Rescheduler as well as a Collision resolver integrated to solve special scenarios not solvable by standard prioritized planning approaches as shown in the figure below. {{attachment:SampleScenario_1_Wait.png||width="49%"}} {{attachment:SampleScenario_2_Avoid.png||width="49%"}} {{attachment:SampleScenario_3_Avoid.png||width="49%"}} {{attachment:SampleScenario_4_Push.png||width="49%"}} {{attachment:SampleScenario_5_Prio.png||width="49%"}} {{attachment:SampleScenario_6_Speed.png||width="49%"}} || ||<99% style="text-align:center">'''Figure Sample Scenarios''' || || The route can be used for multiple vehicles or for just one to plan paths on a given or generated graph. == Multi Robot Mode == The Multi Robot Mode is the default mode. The planner listens to `/robot_info` see how many robots are online and available for planning. A list of goals can be send to `goal` Since the results generated for these scenarios are interdependent, the given routes have to be executed in a synchronized fashion. Therefore, the Router publishes a tuw_multi_robot_msgs/Route containing preconditions, when a robot is allowed to enter a segment. Additionally a unsynchronized version via nav_msgs/Path is published for every robot. == Single Robot Mode == In this mode the planner just plans a path for one robot but on a graph which is faster and depending how the graph was generated saver to drive e.g. on a voronoi graph the path would always be center in the hallway and not cut corners such as A-star. In order to activae this mode have a look on the paramter `path_endpoint_optimization` and `robot_name`. === Example === For an example see the tuw_multi_robot_demo package. === Subscribed Topics === `/robot_info` (`tuw_multi_robot_msgs/RobotInfo`) . Every robot should publish its state `/robot_info. `This is required to let the node know how many robots are available and their location for planning in order to genrerate the a publisher for each robot `map` (`nav_msgs/OccupancyGrid`) . The map used for planning. `segments` (`tuw_multi_robot_msgs/Graph`) . A list of `tuw_multi_robot_msgs/Vertex` describing the voronoi path or an arbitrary hand crafted segment path. `goals` (`tuw_multi_robot_msgs/RobotGoalArray`) . The list of desired robot goals. `/goal` ({{{geometry_msgs}}}`/PoseStamped`) . Exists only in single robot mode to send a goal for one robot === Published Topics === `planner_status` (`tuw_multi_robot_msgs/PlannerStatus`) . The status of the planner for debugging. `[robot_name]/path` (`nav_msgs/Path`) . A unsynchronized path msg for every robot. `[robot_name] `defines namespace of each registed robot via `/robot_info` `[robot_name]/route` (`tuw_multi_robot_msgs/Route`) . A synchronized route for every robot containing segment preconditions. === Parameters === `robot_name` (`string` default: "") . defines a single robots name to active the single robot mode. === RQT Reconfigure Parameters === `voronoi_graph` (`bool` default: "true") . If the graph is generated using the voronoi graph generator this can save computation time. (Additionally it can be checkt if the graph covers the whole free space of the map) `priority_rescheduling` (`bool` default: "true") . Enables priority rescheduling `speed_rescheduling` (`bool` default: "true") . Enables speed rescheduling `router_time_limit_s` (`float` default: "10.0") . Sets the timelimit for the planning approach. (Only for planning) `topic_timeout_s` (`float` default: "10.0") . Sets the timelimit for deleting latched topics. `path_endpoint_optimization` (`bool` default: "false") . Only used if exactly one robot is used for planning. Removes an appropriate amount of endsegments of the path to get shorter routes. `collision_resolver` (`enum` default: "Avoidance") . Enum to select the backtracking strategy to avoid blocking robots. * Avoidance: allows robot to avoid other ones in crossings and wait on a spot. * Backtracking: allows robots to wait in a certain spot for other ones. * None: Standard A-Star planner `goal_mode` (`enum` default: "use_voronoi_goal") . Selects where the last segment is connected to. `router_type` (`enum` default: "standard_router") . Selects the router type * standard_router: A straight forward none multi threaded router * threaded_router_srr: Multi Threaded router which plans every robots route in a single thread. (similar to todo) `nr_threads` (`int` default: "1") . selects the number of threads used for all multi threaded routers == Report a Bug == <> ##i.e.<> ## AUTOGENERATED DON'T DELETE ## CategoryStack