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 );
58 std::string topic_odom_name = robot_name +
"/odom";
59 ROS_DEBUG (
"Multi Robot Router: subscribing to %s", topic_odom_name.c_str() );
62 std::string topic_path_name = robot_name +
"/path_unsynced";
63 ROS_DEBUG (
"Multi Robot Router: advertising on %s", topic_path_name.c_str() );
67 std::string topic_route_name = robot_name +
"/route";
68 ROS_DEBUG (
"Multi Robot Router: advertising on %s", topic_route_name.c_str() );
73 tuw_multi_robot_msgs::RobotInfo &des = *
this;
77 size_t RobotInfo::findIdx (
const std::vector<std::shared_ptr<RobotInfo> > &data,
const std::string &name ) {
78 for (
size_t i = 0; i < data.size(); i++ ) {
79 if ( data[i]->robot_name == name )
return i;
84 std::vector<std::shared_ptr<RobotInfo> >::iterator
RobotInfo::findObj ( std::vector<std::shared_ptr<RobotInfo> > &data,
const std::string &name ) {
85 return std::find_if ( data.begin(), data.end(), [&] (
auto & r ) {
86 return r->robot_name == name;
91 double roll, pitch, yaw;
92 tf::Quaternion q ( pose.pose.orientation.x, pose.pose.orientation.y, pose.pose.orientation.z, pose.pose.orientation.w );
94 Eigen::Vector3d p ( pose.pose.position.x, pose.pose.position.y, yaw );
99 if ( shape == SHAPE_CIRCLE ) {
100 return shape_variables[0];
static std::vector< std::shared_ptr< RobotInfo > >::iterator findObj(std::vector< std::shared_ptr< RobotInfo > > &data, const std::string &name)
void updateOnlineStatus(const float updateTime)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Eigen::Vector3d getPose() const
static size_t findIdx(const std::vector< std::shared_ptr< RobotInfo > > &data, const std::string &name)
Online getOnlineStatus() const
bool compareName(const std::shared_ptr< RobotInfo > data) const
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void callback_odom(const nav_msgs::Odometry &msg)
void initTopics(ros::NodeHandle &n)
void updateInfo(const tuw_multi_robot_msgs::RobotInfo &info)