28 #define POT_HIGH 1.0e10
33 #include <tuw_multi_robot_msgs/Route.h>
35 #include <boost/functional/hash.hpp>
36 #include <boost/regex.hpp>
50 std::string a = boost::regex_replace( this->robot_name, boost::regex(
"[^0-9]*([0-9]+).*"), std::string(
"\\1"));
51 std::string b = boost::regex_replace( robot->robot_name, boost::regex(
"[^0-9]*([0-9]+).*"), std::string(
"\\1"));
53 return std::stoi ( a ) < std::stoi ( b );
59 if( robot_name_as_namespace ) {
60 ns = robot_name +
"/";
62 std::string topic_odom_name = ns +
"odom";
63 ROS_DEBUG (
"Multi Robot Router: subscribing to %s", topic_odom_name.c_str() );
66 std::string topic_path_name = ns +
"path_unsynced";
67 ROS_DEBUG (
"Multi Robot Router: advertising on %s", topic_path_name.c_str() );
71 std::string topic_route_name = ns +
"route";
72 ROS_DEBUG (
"Multi Robot Router: advertising on %s", topic_route_name.c_str() );
77 tuw_multi_robot_msgs::RobotInfo &des = *
this;
81 size_t RobotInfo::findIdx (
const std::vector<std::shared_ptr<RobotInfo> > &data,
const std::string &name ) {
82 for (
size_t i = 0; i < data.size(); i++ ) {
83 if ( data[i]->robot_name == name )
return i;
88 std::vector<std::shared_ptr<RobotInfo> >::iterator
RobotInfo::findObj ( std::vector<std::shared_ptr<RobotInfo> > &data,
const std::string &name ) {
89 return std::find_if ( data.begin(), data.end(), [&] (
auto & r ) {
90 return r->robot_name == name;
95 double roll, pitch, yaw;
96 tf::Quaternion q ( pose.pose.orientation.x, pose.pose.orientation.y, pose.pose.orientation.z, pose.pose.orientation.w );
98 Eigen::Vector3d p ( pose.pose.position.x, pose.pose.position.y, yaw );
103 if ( shape == SHAPE_CIRCLE ) {
104 return shape_variables[0];