Show EOL distros:
Package Summary
This package presents a node, which converts synchronized robot routes to path segments published sequentially to maintain synchronization
- Maintainer status: maintained
- Maintainer: Benjamin Binder <benjamin.binder AT tuwien.ac DOT at>, Markus Bader <markus.bader AT tuwien.ac DOT at>, Florian Beck <florian.beck AT tuwien.ac DOT at>
- Author: Benjamin Binder <benjamin.binder AT tuwien.ac DOT at>
- License: BSD
- Source: git https://github.com/tuw-robotics/tuw_multi_robot.git (branch: kinetic)
Package Summary
This package presents a node, which converts synchronized robot routes to path segments published sequentially to maintain synchronization
- Maintainer status: maintained
- Maintainer: Benjamin Binder <benjamin.binder AT tuwien.ac DOT at>, Markus Bader <markus.bader AT tuwien.ac DOT at>, Florian Beck <florian.beck AT tuwien.ac DOT at>
- Author: Benjamin Binder <benjamin.binder AT tuwien.ac DOT at>
- License: BSD
- Source: git https://github.com/tuw-robotics/tuw_multi_robot.git (branch: melodic)
Package Summary
This package presents a node, which converts synchronized robot routes to path segments published sequentially to maintain synchronization
- Maintainer status: maintained
- Maintainer: Benjamin Binder <benjamin.binder AT tuwien.ac DOT at>, Markus Bader <markus.bader AT tuwien.ac DOT at>, Florian Beck <florian.beck AT tuwien.ac DOT at>
- Author: Benjamin Binder <benjamin.binder AT tuwien.ac DOT at>
- License: BSD
- Source: git https://github.com/tuw-robotics/tuw_multi_robot.git (branch: noetic)
Documentation
This package contains a node, which receives the tuw_multi_robot_msgs/RouteSegment message for a robot and publishes a nav_msgs/Path up to the point a robot is allowed to move.
A tuw_multi_robot_msgs/RouteSegment contains a set of segments, where each of them has preconditions to tell when a robot is allowed to enter a certain segment. The tuw_multi_robot_route_to_path_node subscribes to these messages and checks how many of these preconditions are met and publishes a path from start to the last segment, for which the preconditions are met. This node subscribes to all robots as one node for performance reasons while testing with a large number of robots.
Subscribed Topics
[robot_name]/route (tuw_multi_robot_msgs/Route)
- The segment path containing Preconditions
robot_info (tuw_multi_robot_msgs/RobotInfo)
- Containes the pose of every robot used to determine the current segment on its path.
Published Topics
[robot_name]/path (nav_msgs/Path)
- A unsynchronized path to the last free segment.
robot_info (tuw_multi_robot::RobotInfo)
- Publishes information to all robots used by the behavior planner.
Parameters
~robot_names (string[] default: "[robot_0]")
- Sets the prefixes for all topics (e.g.: /robot_0/route)
~robot_names_str (string default: "")
- A string which overrides the robot_names array to prevent a method of giving the param over console. All robot names have to be seperated by ",".
~robot_radius (float[] default: "[]")
- Sets the radius for a specific robot (matched to the robot in the robot_names list)
~robot_default_radius (float default: "0.3")
- Sets the default radius used if no robot_radius is set for the specific robot
~path_topic (string default: "path")
- The topic used for publishing an unsynchronized nav_msgs/Path for every robot.
~route_topic (string default: "route")
- Topic containing the synchronized Route for every robot.
Report a Bug
Use GitHub to report bugs or submit feature requests. [View active issues]