27 #ifndef TUW_MULTI_ROBOT_ROUTE_TO_PATH_H 28 #define TUW_MULTI_ROBOT_ROUTE_TO_PATH_H 32 #include <nav_msgs/Path.h> 33 #include <nav_msgs/Odometry.h> 34 #include <tuw_multi_robot_msgs/Route.h> 51 std::unique_ptr<ros::Rate>
rate_;
54 void publishPath(std::vector<Eigen::Vector3d> _p,
int _topic);
ros::NodeHandle n_
Node handler to the root node.
std::vector< RobotStateObserver > observer_
void subSegPathCb(const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &_event, int _topic)
std::vector< std::string > robot_names_
void subOdomCb(const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
int findRobotId(std::string _name)
std::vector< ros::Subscriber > subSegPath_
std::string topic_seg_path_
MultiRobotRouteToPathNode(ros::NodeHandle &n)
void publishPath(std::vector< Eigen::Vector3d > _p, int _topic)
std::unique_ptr< ros::Rate > rate_
std::vector< RobotRouteToPath > converter_
std::vector< int > robot_steps_
std::vector< ros::Publisher > pubPath_
ros::NodeHandle n_param_
Node handler to the current node.
std::vector< ros::Subscriber > subOdometry_