29 #ifndef TUW_MULTI_ROBOT_ROBOT_ROUTER_INFO_H
30 #define TUW_MULTI_ROBOT_ROBOT_ROUTER_INFO_H
34 #include <tuw_multi_robot_msgs/RobotGoalsArray.h>
35 #include <tuw_multi_robot_msgs/RobotGoals.h>
36 #include <tuw_multi_robot_msgs/RobotInfo.h>
37 #include <nav_msgs/Odometry.h>
38 #include <tuw_multi_robot_msgs/Graph.h>
39 #include <nav_msgs/Path.h>
40 #include <nav_msgs/OccupancyGrid.h>
41 #include <tuw_multi_robot_msgs/RouterStatus.h>
42 #include <dynamic_reconfigure/server.h>
43 #include <tuw_multi_robot_router/routerConfig.h>
47 #include <opencv2/core/core.hpp>
53 class RobotInfo :
public tuw_multi_robot_msgs::RobotInfo
62 RobotInfo (
const tuw_multi_robot_msgs::RobotInfo& o)
82 void updateInfo(
const tuw_multi_robot_msgs::RobotInfo &info);
101 Eigen::Vector3d
getPose()
const;
106 static size_t findIdx(
const std::vector<std::shared_ptr<RobotInfo> > &data,
const std::string &name);
111 static std::vector<std::shared_ptr<RobotInfo> >::iterator
findObj(std::vector<std::shared_ptr<RobotInfo> > &data,
const std::string &name);
113 bool compareName(
const std::shared_ptr<RobotInfo> data)
const;
127 #endif // TUW_MULTI_ROBOT_ROBOT_ROUTER_INFO_H