1 #include <visualization_msgs/Marker.h>
2 #include <nav2d_msgs/RobotPose.h>
6 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
60 if(mapperNode.
getParam(
"UseScanMatching", param_b))
63 if(mapperNode.
getParam(
"UseScanBarycenter", param_b))
66 if(mapperNode.
getParam(
"MinimumTravelDistance", param_d))
69 if(mapperNode.
getParam(
"MinimumTravelHeading", param_d))
72 if(mapperNode.
getParam(
"ScanBufferSize", param_i))
75 if(mapperNode.
getParam(
"ScanBufferMaximumScanDistance", param_d))
78 if(mapperNode.
getParam(
"UseResponseExpansion", param_b))
81 if(mapperNode.
getParam(
"DistanceVariancePenalty", param_d))
84 if(mapperNode.
getParam(
"MinimumDistancePenalty", param_d))
87 if(mapperNode.
getParam(
"AngleVariancePenalty", param_d))
90 if(mapperNode.
getParam(
"MinimumAnglePenalty", param_d))
93 if(mapperNode.
getParam(
"LinkMatchMinimumResponseFine", param_d))
96 if(mapperNode.
getParam(
"LinkScanMaximumDistance", param_d))
99 if(mapperNode.
getParam(
"CorrelationSearchSpaceDimension", param_d))
102 if(mapperNode.
getParam(
"CorrelationSearchSpaceResolution", param_d))
105 if(mapperNode.
getParam(
"CorrelationSearchSpaceSmearDeviation", param_d))
108 if(mapperNode.
getParam(
"CoarseSearchAngleOffset", param_d))
111 if(mapperNode.
getParam(
"FineSearchAngleOffset", param_d))
114 if(mapperNode.
getParam(
"CoarseAngleResolution", param_d))
117 if(mapperNode.
getParam(
"LoopSearchSpaceDimension", param_d))
120 if(mapperNode.
getParam(
"LoopSearchSpaceResolution", param_d))
123 if(mapperNode.
getParam(
"LoopSearchSpaceSmearDeviation", param_d))
126 if(mapperNode.
getParam(
"LoopSearchMaximumDistance", param_d))
129 if(mapperNode.
getParam(
"LoopMatchMinimumChainSize", param_i))
132 if(mapperNode.
getParam(
"LoopMatchMaximumVarianceCoarse", param_d))
135 if(mapperNode.
getParam(
"LoopMatchMinimumResponseCoarse", param_d))
138 if(mapperNode.
getParam(
"LoopMatchMinimumResponseFine", param_d))
156 ROS_INFO(
"Inititialized robot 1, starting to map now.");
159 geometry_msgs::PoseStamped locResult;
161 locResult.header.frame_id =
mMapFrame.c_str();
162 locResult.pose.position.x = 0;
163 locResult.pose.position.y = 0;
164 locResult.pose.position.z = 0;
171 ROS_INFO(
"Initialized robot %d, waiting for map from robot 1 now.",
mRobotID);
189 transform.
setOrigin(tf::Vector3(x, y, 0));
191 transform = transform.
inverse();
199 transform = pose_out;
209 geometry_msgs::PoseStamped locResult;
211 locResult.header.frame_id =
mMapFrame.c_str();
212 locResult.pose.position.x = x;
213 locResult.pose.position.y = y;
214 locResult.pose.position.z = 0;
228 std::vector<float>::const_iterator it;
229 for(it = scan.ranges.begin(); it != scan.ranges.end(); it++)
231 if(*it >= scan.range_min && *it <= scan.range_max)
235 }
else if( !std::isfinite(*it) && *it < 0)
238 readings.
Add(scan.range_max);
239 }
else if( !std::isfinite(*it) && *it > 0)
242 readings.
Add(scan.range_max);
243 }
else if( std::isnan(*it) )
247 readings.
Add(scan.range_max);
253 readings.
Add(scan.range_max);
271 sprintf(name,
"robot_%d",
mRobotID);
277 mLaser->SetMinimumRange(scan->range_min);
278 mLaser->SetMaximumRange(scan->range_max);
279 mLaser->SetMinimumAngle(scan->angle_min);
280 mLaser->SetMaximumAngle(scan->angle_max);
281 mLaser->SetAngularResolution(scan->angle_increment);
298 ROS_INFO(
"Localization finished on robot %d, now starting to map.",
mRobotID);
319 ROS_WARN(
"Failed to compute odometry pose, skipping scan (%s)", e.what());
346 map_in_robot = map_in_robot.
inverse();
379 nav2d_msgs::RobotPose other;
395 ROS_INFO(
"Still waiting for map from robot 1.");
405 ROS_WARN(
"Serving map request failed!");
423 visualization_msgs::Marker marker;
427 marker.type = visualization_msgs::Marker::SPHERE_LIST;
428 marker.action = visualization_msgs::Marker::ADD;
429 marker.pose.position.x = 0;
430 marker.pose.position.y = 0;
431 marker.pose.position.z = 0;
432 marker.pose.orientation.x = 0.0;
433 marker.pose.orientation.y = 0.0;
434 marker.pose.orientation.z = 0.0;
435 marker.pose.orientation.w = 1.0;
436 marker.scale.x = 0.1;
437 marker.scale.y = 0.1;
438 marker.scale.z = 0.1;
439 marker.color.a = 1.0;
440 marker.color.r = 0.0;
441 marker.color.g = 1.0;
442 marker.color.b = 0.0;
443 marker.points.resize(vertices.
Size());
445 for(
int i = 0; i < vertices.
Size(); i++)
447 marker.points[i].x = vertices[i]->GetVertexObject()->GetCorrectedPose().GetX();
448 marker.points[i].y = vertices[i]->GetVertexObject()->GetCorrectedPose().GetY();
449 marker.points[i].z = 0;
458 marker.type = visualization_msgs::Marker::LINE_LIST;
459 marker.scale.x = 0.01;
460 marker.color.a = 1.0;
461 marker.color.r = 1.0;
462 marker.color.g = 0.0;
463 marker.color.b = 0.0;
464 marker.points.resize(edges.
Size() * 2);
466 for(
int i = 0; i < edges.
Size(); i++)
468 marker.points[2*i].x = edges[i]->GetSource()->GetVertexObject()->GetCorrectedPose().GetX();
469 marker.points[2*i].y = edges[i]->GetSource()->GetVertexObject()->GetCorrectedPose().GetY();
470 marker.points[2*i].z = 0;
472 marker.points[2*i+1].x = edges[i]->GetTarget()->GetVertexObject()->GetCorrectedPose().GetX();
473 marker.points[2*i+1].y = edges[i]->GetTarget()->GetVertexObject()->GetCorrectedPose().GetY();
474 marker.points[2*i+1].z = 0;
490 ROS_WARN(
"Failed to get occupancy map from Karto-Mapper.");
495 unsigned int width = kartoGrid->GetWidth();
496 unsigned int height = kartoGrid->GetHeight();
512 for (
unsigned int y = 0; y < height; y++)
514 for (
unsigned int x = 0; x < width; x++)
531 ROS_WARN(
"Encountered unknown cell value at %d, %d", x, y);
547 if(scan->robot_id ==
mRobotID)
return;
551 sprintf(robot,
"robot_%d", scan->robot_id);
574 laser->SetMinimumRange(scan->scan.range_min);
575 laser->SetMaximumRange(scan->scan.range_max);
576 laser->SetMinimumAngle(scan->scan.angle_min);
577 laser->SetMaximumAngle(scan->scan.angle_max);
578 laser->SetAngularResolution(scan->scan.angle_increment);
581 mOtherLasers.insert(std::pair<int,karto::LaserRangeFinderPtr>(scan->robot_id,laser));
601 nav2d_msgs::RobotPose other;
604 other.robot_id = scan->robot_id;
622 ROS_DEBUG(
"Discarded Scan from Robot %d!", scan->robot_id);
631 ROS_INFO(
"Received a map, now starting to localize.");
638 nav2d_msgs::LocalizedScan rosScan;
640 rosScan.laser_type = 0;
641 rosScan.x = pose.
GetX();
642 rosScan.y = pose.
GetY();
645 rosScan.scan.angle_min = scan->angle_min;
646 rosScan.scan.angle_max = scan->angle_max;
647 rosScan.scan.range_min = scan->range_min;
648 rosScan.scan.range_max = scan->range_max;
649 rosScan.scan.angle_increment = scan->angle_increment;
650 rosScan.scan.time_increment = scan->time_increment;
651 rosScan.scan.scan_time = scan->scan_time;
653 unsigned int nReadings = scan->ranges.size();
654 rosScan.scan.ranges.resize(nReadings);
655 for(
unsigned int i = 0; i < nReadings; i++)
657 rosScan.scan.ranges[i] = scan->ranges[i];
666 double x = pose->pose.pose.position.x;
667 double y = pose->pose.pose.position.y;
668 double yaw =
tf::getYaw(pose->pose.pose.orientation);
669 ROS_INFO(
"Received initial pose (%.2f, %.2f, %.2f) on robot %d, now starting to map.",x,y,yaw,
mRobotID);
683 ROS_DEBUG(
"OpenMapper: %s\n",
args.GetEventMessage().ToCString());