router_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, <copyright holder> <email>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the <organization> nor the
13  * names of its contributors may be used to endorse or promote products
14  * derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY <copyright holder> <email> ''AS IS'' AND ANY
17  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  * DISCLAIMED. IN NO EVENT SHALL <copyright holder> <email> BE LIABLE FOR ANY
20  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  *
27  */
28 #define POT_HIGH 1.0e10
29 
32 #include <tuw_multi_robot_msgs/Route.h>
33 #include <chrono>
34 #include <boost/functional/hash.hpp>
35 #include <boost/regex.hpp>
36 #include <tf/tf.h>
37 #include <opencv2/highgui/highgui.hpp>
38 #include <opencv2/imgproc/imgproc.hpp>
39 
40 //TODO add Weights from robots...
41 
42 int main ( int argc, char **argv ) {
43 
44  ros::init ( argc, argv, "tuw_multi_robot_router" );
46 
47  ros::Rate r ( 1 );
48 
50 
51  while ( ros::ok() ) {
52  r.sleep();
53  ros::spinOnce();
54  node.monitorExecution();
55  node.updateTimeout ( r.expectedCycleTime().toSec() );
56  }
57 
58  return 0;
59 }
60 
61 
62 namespace multi_robot_router {
63 
65  n_ ( _n ),
66  n_param_ ( "~" ),
67  monitor_enabled_ ( false ),
68  attempts_total_(0),
69  attempts_successful_(0),
70  sum_processing_time_total_(.0),
71  sum_processing_time_successful_(.0){
72  id_ = 0;
73 
74 
75 
76  n_param_.param<bool> ( "single_robot_mode", single_robot_mode_, false );
77 
78  // static subscriptions
79  subMap_ = n_.subscribe ( "map", 1, &Router_Node::mapCallback, this );
80  subVoronoiGraph_ = n_.subscribe ( "segments", 1, &Router_Node::graphCallback, this );
81  subRobotInfo_ = n_.subscribe ( "robot_info" , 10000, &Router_Node::robotInfoCallback, this );
82 
83  if ( single_robot_mode_) {
85  ROS_INFO("Single Robot Mode");
87  } else {
89  ROS_INFO("Multi Robot Mode");
90  subGoalSet_ = n_.subscribe ( "goals" , 1, &Router_Node::goalsCallback, this );
91  }
92 
93  //static publishers
94  pubPlannerStatus_ = n_.advertise<tuw_multi_robot_msgs::RouterStatus> ( "planner_status", 1 );
95 
96  //dynamic reconfigure
97  call_type = boost::bind ( &Router_Node::parametersCallback, this, _1, _2 );
98  param_server.setCallback ( call_type );
99 }
100 
102  for ( const RobotInfoPtr robot: active_robots_ ) {
103  std::map<std::string, double>::iterator it = finished_robots_.find ( robot->robot_name );
104  if ( robot->status == tuw_multi_robot_msgs::RobotInfo::STATUS_DRIVING ) {
105  if ( it != finished_robots_.end() ) {
106  finished_robots_.erase ( it );
107  if ( monitor_enabled_ ) {
108  ROS_INFO ( "%10s started!", robot->robot_name.c_str() );
109  }
110  }
111  } else {
112  if ( it == finished_robots_.end() ) {
113  double duration = (ros::Time::now() - time_first_robot_started_).toSec();
114  finished_robots_[robot->robot_name] = duration;
115  int nr_of_driving_robots = active_robots_.size() - finished_robots_.size();
116  if ( monitor_enabled_ ) {
117  ROS_INFO ( "%10s stopped @ %6.2lf sec, %3i robots left", robot->robot_name.c_str(), duration, nr_of_driving_robots );
118  }
119  }
120  }
121  }
122  if ( finished_robots_.size() == active_robots_.size() ) {
123  if ( monitor_enabled_ ) {
125  ROS_INFO ( "Execution finished after %lf sec!", duration.toSec() );
126  std::stringstream ss;
127  for(std::map<std::string, double>::iterator it = finished_robots_.begin(); it!=finished_robots_.end(); ++it){
128  ss << it->second << ", ";
129  }
130  ROS_INFO ( "Duration by robot: \n [%s]", ss.str().c_str() );
131  }
132  monitor_enabled_ = false;
133  } else {
134  monitor_enabled_ = true;
135  }
136 
137 }
138 
139 void Router_Node::goalCallback ( const geometry_msgs::PoseStamped &msg ) {
140 
141  if ( subscribed_robots_.size() != 1 ) {
142  ROS_WARN ( "No robot subsribed, ou have to publish a tuw_multi_robot_msgs::RobotInfo to let the planer know where your robot is located!");
143  ROS_WARN ( "Use a local behavior controller to publish regual a RobotInfo msg!");
144  return;
145  }
146  tuw_multi_robot_msgs::RobotGoalsArray goalsArray;
147  goalsArray.header = msg.header;
148  goalsArray.robots.resize(1);
149  tuw_multi_robot_msgs::RobotGoals &goals = goalsArray.robots[0];
150  goals.robot_name = subscribed_robots_[0]->robot_name;
151  goals.destinations.resize(1);
152  goals.destinations[0] = msg.pose;
153  goalsCallback ( goalsArray );
154 }
155 
156 void Router_Node::updateTimeout ( const float _secs ) {
157  //Todo update timeouts and clear old messages
158  for ( auto it = subscribed_robots_.begin(); it != subscribed_robots_.end(); it++ ) {
159  ( *it )->updateOnlineStatus ( _secs );
160  }
161 }
162 void Router_Node::parametersCallback ( tuw_multi_robot_router::routerConfig &config, uint32_t level ) {
163  //Important set router before settings
164  uint32_t threads = config.nr_threads;
165  if ( config.router_type == 1 )
167  else
169 
170  if ( config.collision_resolver == 0 ){
172  collisionResolver_ = false;
173  } else if ( config.collision_resolver == 1 ) {
175  collisionResolver_ = true;
176  }else{
178  collisionResolver_ = true;
179  }
180 
181  if ( config.voronoi_graph )
183  else
185 
186  if ( config.goal_mode == 0 )
188  else if ( config.goal_mode == 1 )
190  else
192 
193  routerTimeLimit_s_ = config.router_time_limit_s;
194  topic_timeout_s_ = config.topic_timeout_s;
195 
196  priorityRescheduling_ = config.priority_rescheduling;
197  speedRescheduling_ = config.speed_rescheduling;
198  segmentOptimizations_ = config.path_endpoint_optimization;
199  publish_routing_table_ = config.publish_routing_table;
200 }
201 
202 void Router_Node::mapCallback ( const nav_msgs::OccupancyGrid &_map ) {
203  std::vector<signed char> map = _map.data;
204 
205  Eigen::Vector2d origin;
206  origin[0] = _map.info.origin.position.x;
207  origin[1] = _map.info.origin.position.y;
208 
209  size_t new_hash = getHash ( map, origin, _map.info.resolution );
210 
211  ROS_INFO ( "map %f %f %f", origin[0], origin[1], _map.info.resolution );
212 
213  if ( new_hash != current_map_hash_ ) {
214  mapOrigin_[0] = _map.info.origin.position.x;
215  mapOrigin_[1] = _map.info.origin.position.y;
216  mapResolution_ = _map.info.resolution;
217 
218  cv::Mat m ( _map.info.height, _map.info.width, CV_8SC1, map.data() );
219 
220  m.convertTo ( m, CV_8UC1 );
221  cv::bitwise_not ( m, m );
222 
223  cv::threshold ( m, m, 40, 255, cv::THRESH_BINARY | cv::THRESH_OTSU );
224  cv::distanceTransform ( m, distMap_, cv::DIST_L1, 3 );
225 
226  current_map_hash_ = new_hash;
227  got_map_ = true;
228 
229  ROS_INFO ( "%s: New Map %i %i %lu", n_param_.getNamespace().c_str() , _map.info.width, _map.info.height, current_map_hash_ );
230  }
231 }
232 
233 
234 float Router_Node::calcRadius ( const int shape, const std::vector<float> &shape_variables ) const {
235  tuw_multi_robot_msgs::RobotInfo ri;
236  if ( shape == ri.SHAPE_CIRCLE ) {
237  return shape_variables[0];
238  }
239 
240  return -1;
241 }
242 
243 void Router_Node::robotInfoCallback ( const tuw_multi_robot_msgs::RobotInfo &_robotInfo ) {
244 
245  auto robot = RobotInfo::findObj ( subscribed_robots_, _robotInfo.robot_name );
246  if ( robot == subscribed_robots_.end() ) {
247  // create new entry
248  RobotInfoPtr robot_new = std::make_shared<RobotInfo> ( _robotInfo );
249  robot_new->initTopics ( n_ , !single_robot_mode_);
250  subscribed_robots_.push_back ( robot_new );
251  } else {
252  ( *robot )->updateInfo ( _robotInfo );
253  }
254 
255  robot_radius_max_ = 0;
256  for ( RobotInfoPtr &r: subscribed_robots_ ) {
257  if ( r->radius() > robot_radius_max_ )
258  robot_radius_max_ = r->radius();
259  }
260  if(single_robot_mode_ && (subscribed_robots_.size() > 1)){
261  ROS_WARN("More than one robot subsribed, but the MRRP is in single robot mode");
262  }
263 }
264 
265 void Router_Node::graphCallback ( const tuw_multi_robot_msgs::Graph &msg ) {
266 
267  if (!got_map_) {
268  ROS_INFO("No map received. Waiting...");
269  return;
270  }
271 
272  std::vector<Segment> graph;
273 
274  for ( const tuw_multi_robot_msgs::Vertex &segment : msg.vertices ) {
275  std::vector<Eigen::Vector2d> points;
276 
277  for ( const geometry_msgs::Point &point : segment.path ) {
278  points.emplace_back ( point.x / mapResolution_, point.y / mapResolution_);
279  }
280 
281  std::vector<uint32_t> successors;
282 
283  for ( const auto &succ : segment.successors ) {
284  successors.emplace_back ( succ );
285  }
286 
287  std::vector<uint32_t> predecessors;
288 
289  for ( const auto &pred : segment.predecessors ) {
290  predecessors.emplace_back ( pred );
291  }
292 
293  if ( segment.valid ) {
294  graph.emplace_back ( segment.id, points, successors, predecessors, 2 * robot_radius_max_ / mapResolution_ ); //segment.width);
295  } else {
296  graph.emplace_back ( segment.id, points, successors, predecessors, 0 );
297  }
298  }
299 
300  std::sort ( graph.begin(), graph.end(), sortSegments );
301 
302  size_t hash = getHash ( graph );
303 
304  if ( current_graph_hash_ != hash ) {
305  current_graph_hash_ = hash;
306  graph_ = graph;
307  ROS_INFO ( "%s: Graph %lu", n_param_.getNamespace().c_str() , hash );
308  }
309  got_graph_ = true;
310 }
311 
312 bool Router_Node::preparePlanning ( std::vector<float> &_radius, std::vector<Eigen::Vector3d> &_starts, std::vector<Eigen::Vector3d> &_goals, const tuw_multi_robot_msgs::RobotGoalsArray &goal_msg, std::vector<std::string> &robot_names ) {
313  bool retval = true;
314  active_robots_.clear();
315  _starts.clear();
316  _goals.clear();
317  _radius.clear();
318 
319  for ( int k = 0; k < goal_msg.robots.size(); k++ ) {
320  const tuw_multi_robot_msgs::RobotGoals &route_request = goal_msg.robots[k];
321  RobotInfoPtrIterator active_robot = RobotInfo::findObj ( subscribed_robots_, route_request.robot_name );
322  if ( active_robot == subscribed_robots_.end() ) {
323  ROS_INFO ( "No robot subsribed with the name: %s", route_request.robot_name.c_str() );
324  } else {
325  if ( route_request.destinations.empty() ) {
326  ROS_INFO ( "No robot: %s has not goal defined", route_request.robot_name.c_str() );
327  continue;
328  } else {
329 
330  active_robots_.push_back ( *active_robot );
331 
332  _radius.push_back ( ( *active_robot )->radius() );
333  if ( route_request.destinations.size() > 1 ) {
334  geometry_msgs::Pose p = route_request.destinations[0];
335  _starts.push_back ( Eigen::Vector3d ( p.position.x, p.position.y, getYaw ( p.orientation ) ) );
336  } else {
337  _starts.push_back ( ( *active_robot )->getPose() );
338  }
339 
340  geometry_msgs::Pose p = route_request.destinations.back();
341  _goals.push_back ( Eigen::Vector3d ( p.position.x, p.position.y, getYaw ( p.orientation ) ) );
342  }
343 
344  }
345  }
346  robot_names.resize ( active_robots_.size() );
347  for ( size_t i=0; i < active_robots_.size(); i++ ) {
348  robot_names[i] = active_robots_[i]->robot_name;
349  }
350  return retval;
351 }
352 
353 void Router_Node::goalsCallback ( const tuw_multi_robot_msgs::RobotGoalsArray &_goals ) {
354  //Get robots
355  std::vector<Eigen::Vector3d> starts;
356  std::vector<Eigen::Vector3d> goals;
357  std::vector<float> radius;
358  std::vector<std::string> robot_names;
359 
360 
361 
362  bool preparationSuccessful = preparePlanning ( radius, starts, goals, _goals, robot_names );
363  ROS_INFO ( "%s: Number of active robots %lu", n_param_.getNamespace().c_str(), active_robots_.size() );
364 
365  if ( preparationSuccessful && got_map_ && got_graph_ ) {
366  attempts_total_++;
367  auto t1 = std::chrono::high_resolution_clock::now();
368  preparationSuccessful &= makePlan ( starts, goals, radius, distMap_, mapResolution_, mapOrigin_, graph_, robot_names );
369  auto t2 = std::chrono::high_resolution_clock::now();
370  int duration = std::chrono::duration_cast<std::chrono::milliseconds> ( t2 - t1 ).count();
371  sum_processing_time_total_ += duration;
372  if ( preparationSuccessful ) {
373  int nx = distMap_.cols;
374  int ny = distMap_.rows;
375 
376  double res = mapResolution_;
377  int cx = mapOrigin_[0];
378  int cy = mapOrigin_[1];
379 
380  publish();
383  freshPlan_ = false;
384  } else {
385  publishEmpty();
386  }
387  float rate_success = ((float) attempts_successful_) / (float) attempts_total_;
388  float avr_duration_total = sum_processing_time_total_ / (float) attempts_total_;
389  float avr_duration_successful = sum_processing_time_successful_ / (float) attempts_successful_;
390  ROS_INFO ( "\nSuccess %i, %i = %4.3f, avr %4.0f ms, success: %4.0f ms, %s, %s, %s \n [%4.3f, %4.0f, %4.0f]",
391  attempts_successful_, attempts_total_, rate_success, avr_duration_total, avr_duration_successful,
392  (priorityRescheduling_?"PR= on":"PR= off"), (speedRescheduling_?"SR= on":"SR= off"), (collisionResolver_?"CR= on":"CR= off"),
393  rate_success, avr_duration_total, avr_duration_successful);
394 
395 
396  id_++;
397  } else if ( !got_map_ || !got_graph_ ) {
398  publishEmpty();
399  ROS_INFO ( "%s: Multi Robot Router: No Map or Graph received", n_param_.getNamespace().c_str() );
400  } else {
401  publishEmpty();
402  }
403 }
404 
405 float Router_Node::getYaw ( const geometry_msgs::Quaternion &_rot ) {
406  double roll, pitch, yaw;
407 
408  tf::Quaternion q ( _rot.x, _rot.y, _rot.z, _rot.w );
409  tf::Matrix3x3 ( q ).getRPY ( roll, pitch, yaw );
410  return yaw;
411 }
412 
414  if(publish_routing_table_ == false) return;
415  ROS_INFO ( "%s: No Plan found!!!!, publishing empty plan", n_param_.getNamespace().c_str());
417  finished_robots_.clear();
418  nav_msgs::Path msg_path;
419  tuw_multi_robot_msgs::Route msg_route;
420  msg_path.header.seq = 0;
421  msg_path.header.stamp = time_first_robot_started_;
422  msg_path.header.frame_id = "map";
423  msg_route.header = msg_path.header;
424 
425  for ( RobotInfoPtr &robot: subscribed_robots_ ) {
426  robot->pubPaths_.publish ( msg_path );
427  robot->pubRoute_.publish ( msg_route );
428  }
429 
430  mrrp_status_.id = id_;
431  mrrp_status_.success = 0;
432  mrrp_status_.duration = getDuration_ms();
434 }
435 
437  if(publish_routing_table_ == false) return;
438  ROS_INFO ( "%s: Plan found :-), publishing plan", n_param_.getNamespace().c_str());
440  finished_robots_.clear();
441  nav_msgs::Path msg_path;
442  tuw_multi_robot_msgs::Route msg_route;
443  msg_path.header.seq = 0;
444  msg_path.header.stamp = time_first_robot_started_;
445  msg_path.header.frame_id = "map";
446  msg_route.header = msg_path.header;
447 
448  for ( int i = 0; i < active_robots_.size(); i++ ) {
449  RobotInfoPtr robot = active_robots_[i];
450  const std::vector<Checkpoint> &route = getRoute ( i );
451  msg_path.poses.clear();
452 
453  //Add first point
454  geometry_msgs::PoseStamped pose_1;
455  pose_1.header.seq = 0;
456  pose_1.header.stamp = time_first_robot_started_;
457  pose_1.header.frame_id = "map";
458 
459  Eigen::Vector2d pos ( route[0].start[0] * mapResolution_, route[0].start[1] * mapResolution_ );
460  pose_1.pose.position.x = pos[0] + mapOrigin_[0];
461  pose_1.pose.position.y = pos[1] + mapOrigin_[1];
462 
463  pose_1.pose.orientation.w = 1;
464  msg_path.poses.push_back ( pose_1 );
465 
466  //Add other points
467  for ( const Checkpoint &c : route ) {
468  geometry_msgs::PoseStamped pose;
469  pose.header.seq = 0;
470  pose.header.stamp = time_first_robot_started_;
471  pose.header.frame_id = "map";
472 
473  Eigen::Vector2d pos ( c.end[0] * mapResolution_, c.end[1] * mapResolution_ );
474  pose.pose.position.x = pos[0] + mapOrigin_[0];
475  pose.pose.position.y = pos[1] + mapOrigin_[1];
476 
478  q.setEuler ( 0, 0, c.end[2] );
479 
480  pose.pose.orientation.w = q.w();
481  pose.pose.orientation.x = q.x();
482  pose.pose.orientation.y = q.y();
483  pose.pose.orientation.z = q.z();
484  msg_path.poses.push_back ( pose );
485  }
486 
487  robot->pubPaths_.publish ( msg_path );
488 
489 
490  msg_route.segments.clear();
491 
492  for ( const Checkpoint &cp : route ) {
493  tuw_multi_robot_msgs::RouteSegment seg;
494 
495  Eigen::Vector2d posStart ( cp.start[0] * mapResolution_, cp.start[1] * mapResolution_ );
496  tf::Quaternion qStart;
497  qStart.setEuler ( 0, 0, cp.start[2] );
498 
499  seg.start.position.x = posStart[0] + mapOrigin_[0];
500  seg.start.position.y = posStart[1] + mapOrigin_[1];
501  seg.start.orientation.w = qStart.w();
502  seg.start.orientation.x = qStart.x();
503  seg.start.orientation.y = qStart.y();
504  seg.start.orientation.z = qStart.z();
505 
506  Eigen::Vector2d posEnd ( cp.end[0] * mapResolution_, cp.end[1] * mapResolution_ );
507  tf::Quaternion qEnd;
508  qEnd.setEuler ( 0, 0, cp.end[2] );
509 
510  seg.end.position.x = posEnd[0] + mapOrigin_[0];
511  seg.end.position.y = posEnd[1] + mapOrigin_[1];
512  seg.end.orientation.w = qEnd.w();
513  seg.end.orientation.x = qEnd.x();
514  seg.end.orientation.y = qEnd.y();
515  seg.end.orientation.z = qEnd.z();
516 
517  seg.segment_id = cp.segId;
518  seg.width = graph_[cp.segId].width() * mapResolution_;
519 
520  for ( int j = 0; j < cp.preconditions.size(); j++ ) {
521  tuw_multi_robot_msgs::RoutePrecondition pc;
522  pc.robot_id = active_robots_[cp.preconditions[j].robotId]->robot_name;
523  pc.current_route_segment = cp.preconditions[j].stepCondition;
524  seg.preconditions.push_back ( pc );
525  }
526 
527  msg_route.segments.push_back ( seg );
528  }
529 
530  robot->pubRoute_.publish ( msg_route );
531  }
532 
533  tuw_multi_robot_msgs::RouterStatus ps;
534  ps.id = id_;
535  ps.success = 1;
536  ps.overall_path_length = ( int32_t ) getOverallPathLength();
537  ps.longest_path_length = ( int32_t ) getLongestPathLength();
538  ps.priority_scheduling_attemps = ( int32_t ) getPriorityScheduleAttemps();
539  ps.speed_scheduling_attemps = ( int32_t ) getSpeedScheduleAttemps();
540  ps.duration = ( int32_t ) getDuration_ms();
541 
542  pubPlannerStatus_.publish ( ps );
543 }
544 
545 size_t Router_Node::getHash ( const std::vector<signed char> &_map, const Eigen::Vector2d &_origin, const float &_resolution ) {
546  std::size_t seed = 0;
547 
548  boost::hash_combine ( seed, _origin[0] );
549  boost::hash_combine ( seed, _origin[1] );
550  boost::hash_combine ( seed, _resolution );
551 
552  for ( const signed char &val : _map ) {
553  boost::hash_combine ( seed, val );
554  }
555 
556  return seed;
557 }
558 
559 std::size_t Router_Node::getHash ( const std::vector<Segment> &_graph ) {
560  std::size_t seed = 0;
561 
562  for ( const Segment &seg : _graph ) {
563  boost::hash_combine ( seed, seg.width() );
564  boost::hash_combine ( seed, seg.length() );
565  boost::hash_combine ( seed, seg.getSegmentId() );
566 
567  for ( const int &p : seg.getPredecessors() ) {
568  boost::hash_combine ( seed, p );
569  }
570 
571  for ( const int &s : seg.getSuccessors() ) {
572  boost::hash_combine ( seed, s );
573  }
574 
575  for ( const Eigen::Vector2d &vec : seg.getPoints() ) {
576  boost::hash_combine ( seed, vec[0] );
577  boost::hash_combine ( seed, vec[1] );
578  }
579  }
580 
581  return seed;
582 }
583 
584 
585 
586 
587 } // namespace multi_robot_router
588 
589 
multi_robot_router::Router::routerTimeLimit_s_
float routerTimeLimit_s_
Definition: router.h:155
tf::Matrix3x3
multi_robot_router::Router::getOverallPathLength
float getOverallPathLength() const
getter
Definition: router.cpp:474
multi_robot_router::Router_Node::sum_processing_time_total_
double sum_processing_time_total_
Definition: router_node.h:86
multi_robot_router::Router_Node::sum_processing_time_successful_
double sum_processing_time_successful_
Definition: router_node.h:87
multi_robot_router::RobotInfo::findObj
static std::vector< std::shared_ptr< RobotInfo > >::iterator findObj(std::vector< std::shared_ptr< RobotInfo > > &data, const std::string &name)
Definition: robot_info.cpp:88
ros::Rate::expectedCycleTime
Duration expectedCycleTime() const
multi_robot_router::Router::setPlannerType
void setPlannerType(routerType _type, uint32_t _nr_threads)
Definition: router.cpp:59
multi_robot_router::Router::getSpeedScheduleAttemps
uint32_t getSpeedScheduleAttemps() const
getter
Definition: router.cpp:484
multi_robot_router::Router_Node::current_map_hash_
size_t current_map_hash_
Definition: router_node.h:117
multi_robot_router::SegmentExpander::CollisionResolverType::backtracking
@ backtracking
multi_robot_router::Router_Node::updateTimeout
void updateTimeout(const float _secs)
used to update the nodes timeout to latch topics
Definition: router_node.cpp:156
multi_robot_router::Router_Node::pubPlannerStatus_
ros::Publisher pubPlannerStatus_
Definition: router_node.h:95
multi_robot_router::Router::getDuration_ms
uint32_t getDuration_ms() const
getter
Definition: router.cpp:464
multi_robot_router::Router_Node::current_graph_hash_
size_t current_graph_hash_
Definition: router_node.h:118
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
multi_robot_router::Router_Node::monitorExecution
void monitorExecution()
monitors the execution
Definition: router_node.cpp:101
multi_robot_router::Router::getRoute
const std::vector< Checkpoint > & getRoute(const uint32_t _robot) const
returns the found Routing Table
Definition: router.cpp:459
multi_robot_router::Router_Node::id_
int id_
Definition: router_node.h:119
tf::Matrix3x3::getRPY
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
multi_robot_router::Router::goalMode::use_voronoi_goal
@ use_voronoi_goal
s
XmlRpcServer s
multi_robot_router::Router::segmentOptimizations_
bool segmentOptimizations_
Definition: router.h:156
multi_robot_router::Router::goalMode_
goalMode goalMode_
Definition: router.h:154
multi_robot_router::Router_Node::sortSegments
static bool sortSegments(const Segment &i, const Segment &j)
Definition: router_node.h:133
multi_robot_router::Router_Node::call_type
dynamic_reconfigure::Server< tuw_multi_robot_router::routerConfig >::CallbackType call_type
Definition: router_node.h:94
multi_robot_router::Router::setCollisionResolutionType
void setCollisionResolutionType(const SegmentExpander::CollisionResolverType _cr)
sets the CollisionResolverType used
Definition: router.cpp:54
multi_robot_router::Router::graphType::voronoi
@ voronoi
ros::spinOnce
ROSCPP_DECL void spinOnce()
multi_robot_router::Router_Node::subscribed_robots_
std::vector< RobotInfoPtr > subscribed_robots_
Definition: router_node.h:104
multi_robot_router::Router_Node::mapCallback
void mapCallback(const nav_msgs::OccupancyGrid &_map)
Definition: router_node.cpp:202
multi_robot_router::Router_Node::subGoalSet_
ros::Subscriber subGoalSet_
Definition: router_node.h:98
multi_robot_router::Router_Node::finished_robots_
std::map< std::string, double > finished_robots_
robots currently used by the planner
Definition: router_node.h:106
multi_robot_router::Router_Node::freshPlan_
bool freshPlan_
Definition: router_node.h:121
multi_robot_router::Router_Node::param_server
dynamic_reconfigure::Server< tuw_multi_robot_router::routerConfig > param_server
Definition: router_node.h:93
multi_robot_router::Router_Node::publishEmpty
void publishEmpty()
publishes an empty RoutingTable
Definition: router_node.cpp:413
multi_robot_router::SegmentExpander::CollisionResolverType::avoidance
@ avoidance
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
srr_utils.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
multi_robot_router::Router_Node::calcRadius
float calcRadius(const int shape, const std::vector< float > &shape_variables) const
Definition: router_node.cpp:234
multi_robot_router::Router_Node::n_param_
ros::NodeHandle n_param_
Node handler to the current node.
Definition: router_node.h:80
multi_robot_router::Router_Node::attempts_successful_
int attempts_successful_
Definition: router_node.h:85
multi_robot_router::Router_Node::got_graph_
bool got_graph_
Definition: router_node.h:115
multi_robot_router::Checkpoint
Definition: mrr_utils.h:42
multi_robot_router::Router::goalMode::use_segment_goal
@ use_segment_goal
multi_robot_router::Router_Node::preparePlanning
bool preparePlanning(std::vector< float > &_radius, std::vector< Eigen::Vector3d > &_starts, std::vector< Eigen::Vector3d > &_goals, const tuw_multi_robot_msgs::RobotGoalsArray &_ros_goals, std::vector< std::string > &robot_names)
Definition: router_node.cpp:312
multi_robot_router::Router_Node::active_robots_
std::vector< RobotInfoPtr > active_robots_
robots avaliable
Definition: router_node.h:105
multi_robot_router::Router_Node::single_robot_mode_
bool single_robot_mode_
Definition: router_node.h:112
multi_robot_router::Router::makePlan
bool makePlan(const std::vector< Eigen::Vector3d > &_starts, const std::vector< Eigen::Vector3d > &_goals, const std::vector< float > &_radius, const cv::Mat &_map, const float &_resolution, const Eigen::Vector2d &_origin, const std::vector< Segment > &_graph, const std::vector< std::string > &_robot_names)
generates the plan from (Vertex[odom robotPose] to Vertex[_goals]
Definition: router.cpp:328
multi_robot_router::Router_Node::attempts_total_
int attempts_total_
Definition: router_node.h:84
multi_robot_router::RobotInfoPtr
std::shared_ptr< RobotInfo > RobotInfoPtr
Definition: robot_info.h:123
q
std::queue< Index > q
multi_robot_router::Router_Node::monitor_enabled_
bool monitor_enabled_
Definition: router_node.h:122
multi_robot_router::Router_Node::subMap_
ros::Subscriber subMap_
Definition: router_node.h:99
multi_robot_router::Router::goalMode::use_map_goal
@ use_map_goal
multi_robot_router::Router_Node::graph_
std::vector< Segment > graph_
Definition: router_node.h:116
multi_robot_router::Router::graphType::random
@ random
multi_robot_router::Router::collisionResolver_
bool collisionResolver_
Definition: router.h:159
multi_robot_router::RobotInfoPtrIterator
std::vector< std::shared_ptr< RobotInfo > >::iterator RobotInfoPtrIterator
Definition: robot_info.h:124
multi_robot_router::Router_Node::subVoronoiGraph_
ros::Subscriber subVoronoiGraph_
Definition: router_node.h:101
multi_robot_router::Router::priorityRescheduling_
bool priorityRescheduling_
Definition: router.h:158
multi_robot_router::Router_Node::goalsCallback
void goalsCallback(const tuw_multi_robot_msgs::RobotGoalsArray &_goals)
Definition: router_node.cpp:353
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
multi_robot_router::Router_Node::robotInfoCallback
void robotInfoCallback(const tuw_multi_robot_msgs::RobotInfo &_robotInfo)
Definition: router_node.cpp:243
multi_robot_router::Router_Node::graphCallback
void graphCallback(const tuw_multi_robot_msgs::Graph &msg)
Definition: router_node.cpp:265
multi_robot_router::Router_Node::mrrp_status_
tuw_multi_robot_msgs::RouterStatus mrrp_status_
Definition: router_node.h:91
multi_robot_router::Router::graphMode_
graphType graphMode_
Definition: router.h:153
multi_robot_router::Router_Node::publish
void publish()
publishes a RoutingTable
Definition: router_node.cpp:436
ros::Rate::sleep
bool sleep()
multi_robot_router::Router_Node::Router_Node
Router_Node(ros::NodeHandle &n)
Construct a new Router_Node object.
Definition: router_node.cpp:64
multi_robot_router::Router::routerType::multiThreadSrr
@ multiThreadSrr
multi_robot_router::Router::speedRescheduling_
bool speedRescheduling_
Definition: router.h:157
tf.h
start
ROSCPP_DECL void start()
multi_robot_router::Router_Node::distMap_
cv::Mat distMap_
Definition: router_node.h:109
multi_robot_router::Router_Node::got_map_
bool got_map_
Definition: router_node.h:114
router_node.h
multi_robot_router::Router::getLongestPathLength
float getLongestPathLength() const
getter
Definition: router.cpp:469
multi_robot_router::Router::routerType::singleThread
@ singleThread
main
int main(int argc, char **argv)
Definition: router_node.cpp:42
multi_robot_router::Router_Node::topic_timeout_s_
float topic_timeout_s_
Definition: router_node.h:120
multi_robot_router::Router
Definition: router.h:41
multi_robot_router::Router_Node::mapResolution_
float mapResolution_
Definition: router_node.h:111
multi_robot_router::Segment
Definition: srr_utils.h:41
multi_robot_router::Router_Node::subRobotInfo_
ros::Subscriber subRobotInfo_
Definition: router_node.h:102
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
multi_robot_router::Router_Node::n_
ros::NodeHandle n_
Node handler to the root node.
Definition: router_node.h:79
tf::Quaternion::setEuler
void setEuler(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
multi_robot_router::Router_Node::getHash
size_t getHash(const std::vector< signed char > &_map, const Eigen::Vector2d &_origin, const float &_resolution)
Definition: router_node.cpp:545
ros::Rate
multi_robot_router::Router_Node::getYaw
float getYaw(const geometry_msgs::Quaternion &_rot)
Definition: router_node.cpp:405
multi_robot_router::Router_Node::mapOrigin_
Eigen::Vector2d mapOrigin_
Definition: router_node.h:110
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
DurationBase< Duration >::toSec
double toSec() const
multi_robot_router::Router::getPriorityScheduleAttemps
uint32_t getPriorityScheduleAttemps() const
getter
Definition: router.cpp:479
multi_robot_router::Router_Node::robot_radius_max_
float robot_radius_max_
Definition: router_node.h:108
ROS_INFO
#define ROS_INFO(...)
multi_robot_router::Router_Node::parametersCallback
void parametersCallback(tuw_multi_robot_router::routerConfig &config, uint32_t level)
Definition: router_node.cpp:162
multi_robot_router::SegmentExpander::CollisionResolverType::none
@ none
multi_robot_router::Router_Node::goalCallback
void goalCallback(const geometry_msgs::PoseStamped &_goal)
Definition: router_node.cpp:139
multi_robot_router::Router_Node::time_first_robot_started_
ros::Time time_first_robot_started_
Definition: router_node.h:89
ros::Duration
tf::Quaternion
multi_robot_router
Definition: avoidance_resolution.h:37
multi_robot_router::Router_Node::subSingleRobotGoal_
ros::Subscriber subSingleRobotGoal_
Definition: router_node.h:100
multi_robot_router::Router_Node::publish_routing_table_
bool publish_routing_table_
Definition: router_node.h:113
ros::NodeHandle
ros::Time::now
static Time now()
multi_robot_router::Router_Node
Definition: router_node.h:53


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:10:16