28 #define POT_HIGH 1.0e10
32 #include <tuw_multi_robot_msgs/Route.h>
34 #include <boost/functional/hash.hpp>
35 #include <boost/regex.hpp>
37 #include <opencv2/highgui/highgui.hpp>
38 #include <opencv2/imgproc/imgproc.hpp>
42 int main (
int argc,
char **argv ) {
44 ros::init ( argc, argv,
"tuw_multi_robot_router" );
67 monitor_enabled_ ( false ),
69 attempts_successful_(0),
70 sum_processing_time_total_(.0),
71 sum_processing_time_successful_(.0){
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 ) {
108 ROS_INFO (
"%10s started!", robot->robot_name.c_str() );
117 ROS_INFO (
"%10s stopped @ %6.2lf sec, %3i robots left", robot->robot_name.c_str(), duration, nr_of_driving_robots );
125 ROS_INFO (
"Execution finished after %lf sec!", duration.
toSec() );
126 std::stringstream ss;
128 ss << it->second <<
", ";
130 ROS_INFO (
"Duration by robot: \n [%s]", ss.str().c_str() );
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!");
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];
151 goals.destinations.resize(1);
152 goals.destinations[0] = msg.pose;
159 ( *it )->updateOnlineStatus ( _secs );
164 uint32_t threads = config.nr_threads;
165 if ( config.router_type == 1 )
170 if ( config.collision_resolver == 0 ){
173 }
else if ( config.collision_resolver == 1 ) {
181 if ( config.voronoi_graph )
186 if ( config.goal_mode == 0 )
188 else if ( config.goal_mode == 1 )
203 std::vector<signed char> map = _map.data;
205 Eigen::Vector2d origin;
206 origin[0] = _map.info.origin.position.x;
207 origin[1] = _map.info.origin.position.y;
209 size_t new_hash =
getHash ( map, origin, _map.info.resolution );
211 ROS_INFO (
"map %f %f %f", origin[0], origin[1], _map.info.resolution );
218 cv::Mat m ( _map.info.height, _map.info.width, CV_8SC1, map.data() );
220 m.convertTo ( m, CV_8UC1 );
221 cv::bitwise_not ( m, m );
223 cv::threshold ( m, m, 40, 255, cv::THRESH_BINARY | cv::THRESH_OTSU );
224 cv::distanceTransform ( m,
distMap_, cv::DIST_L1, 3 );
235 tuw_multi_robot_msgs::RobotInfo ri;
236 if ( shape == ri.SHAPE_CIRCLE ) {
237 return shape_variables[0];
248 RobotInfoPtr robot_new = std::make_shared<RobotInfo> ( _robotInfo );
252 ( *robot )->updateInfo ( _robotInfo );
261 ROS_WARN(
"More than one robot subsribed, but the MRRP is in single robot mode");
268 ROS_INFO(
"No map received. Waiting...");
272 std::vector<Segment> graph;
274 for (
const tuw_multi_robot_msgs::Vertex &segment : msg.vertices ) {
275 std::vector<Eigen::Vector2d> points;
277 for (
const geometry_msgs::Point &point : segment.path ) {
281 std::vector<uint32_t> successors;
283 for (
const auto &succ : segment.successors ) {
284 successors.emplace_back ( succ );
287 std::vector<uint32_t> predecessors;
289 for (
const auto &pred : segment.predecessors ) {
290 predecessors.emplace_back ( pred );
293 if ( segment.valid ) {
296 graph.emplace_back ( segment.id, points, successors, predecessors, 0 );
302 size_t hash =
getHash ( graph );
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 ) {
319 for (
int k = 0; k < goal_msg.robots.size(); k++ ) {
320 const tuw_multi_robot_msgs::RobotGoals &route_request = goal_msg.robots[k];
323 ROS_INFO (
"No robot subsribed with the name: %s", route_request.robot_name.c_str() );
325 if ( route_request.destinations.empty() ) {
326 ROS_INFO (
"No robot: %s has not goal defined", route_request.robot_name.c_str() );
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 ) ) );
337 _starts.push_back ( ( *active_robot )->getPose() );
340 geometry_msgs::Pose p = route_request.destinations.back();
341 _goals.push_back ( Eigen::Vector3d ( p.position.x, p.position.y,
getYaw ( p.orientation ) ) );
355 std::vector<Eigen::Vector3d> starts;
356 std::vector<Eigen::Vector3d> goals;
357 std::vector<float> radius;
358 std::vector<std::string> robot_names;
362 bool preparationSuccessful =
preparePlanning ( radius, starts, goals, _goals, robot_names );
367 auto t1 = std::chrono::high_resolution_clock::now();
369 auto t2 = std::chrono::high_resolution_clock::now();
370 int duration = std::chrono::duration_cast<std::chrono::milliseconds> ( t2 - t1 ).count();
372 if ( preparationSuccessful ) {
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]",
393 rate_success, avr_duration_total, avr_duration_successful);
406 double roll, pitch, yaw;
418 nav_msgs::Path msg_path;
419 tuw_multi_robot_msgs::Route msg_route;
420 msg_path.header.seq = 0;
422 msg_path.header.frame_id =
"map";
423 msg_route.header = msg_path.header;
426 robot->pubPaths_.publish ( msg_path );
427 robot->pubRoute_.publish ( msg_route );
441 nav_msgs::Path msg_path;
442 tuw_multi_robot_msgs::Route msg_route;
443 msg_path.header.seq = 0;
445 msg_path.header.frame_id =
"map";
446 msg_route.header = msg_path.header;
450 const std::vector<Checkpoint> &route =
getRoute ( i );
451 msg_path.poses.clear();
454 geometry_msgs::PoseStamped pose_1;
455 pose_1.header.seq = 0;
457 pose_1.header.frame_id =
"map";
460 pose_1.pose.position.x = pos[0] +
mapOrigin_[0];
461 pose_1.pose.position.y = pos[1] +
mapOrigin_[1];
463 pose_1.pose.orientation.w = 1;
464 msg_path.poses.push_back ( pose_1 );
468 geometry_msgs::PoseStamped pose;
471 pose.header.frame_id =
"map";
474 pose.pose.position.x = pos[0] +
mapOrigin_[0];
475 pose.pose.position.y = pos[1] +
mapOrigin_[1];
478 q.setEuler ( 0, 0, c.end[2] );
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 );
487 robot->pubPaths_.publish ( msg_path );
490 msg_route.segments.clear();
493 tuw_multi_robot_msgs::RouteSegment seg;
497 qStart.
setEuler ( 0, 0, cp.start[2] );
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();
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();
517 seg.segment_id = cp.segId;
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 );
527 msg_route.segments.push_back ( seg );
530 robot->pubRoute_.publish ( msg_route );
533 tuw_multi_robot_msgs::RouterStatus ps;
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;
548 boost::hash_combine ( seed, _origin[0] );
549 boost::hash_combine ( seed, _origin[1] );
550 boost::hash_combine ( seed, _resolution );
552 for (
const signed char &val : _map ) {
553 boost::hash_combine ( seed, val );
560 std::size_t seed = 0;
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() );
567 for (
const int &p : seg.getPredecessors() ) {
568 boost::hash_combine ( seed, p );
571 for (
const int &
s : seg.getSuccessors() ) {
572 boost::hash_combine ( seed,
s );
575 for (
const Eigen::Vector2d &vec : seg.getPoints() ) {
576 boost::hash_combine ( seed, vec[0] );
577 boost::hash_combine ( seed, vec[1] );