MultiMapper.cpp
Go to the documentation of this file.
00001 #include <visualization_msgs/Marker.h>
00002 #include <nav2d_msgs/RobotPose.h>
00003 #include <nav2d_karto/MultiMapper.h>
00004 
00005 // compute linear index for given map coords
00006 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
00007 
00008 
00009 MultiMapper::MultiMapper()
00010 {
00011         // Get parameters from the ROS parameter server
00012         ros::NodeHandle robotNode;
00013         robotNode.param("robot_id", mRobotID, 1);
00014         robotNode.param("scan_input_topic", mScanInputTopic, std::string("karto_in"));
00015         robotNode.param("scan_output_topic", mScanOutputTopic, std::string("karto_out"));
00016         robotNode.param("laser_frame", mLaserFrame, std::string("laser"));
00017         robotNode.param("robot_frame", mRobotFrame, std::string("robot"));
00018         robotNode.param("odometry_frame", mOdometryFrame, std::string("odometry_base"));
00019         robotNode.param("offset_frame", mOffsetFrame, std::string("odometry_offset"));
00020         robotNode.param("map_frame", mMapFrame, std::string("map"));
00021         robotNode.param("map_service", mMapService, std::string("get_map"));
00022         robotNode.param("laser_topic", mLaserTopic, std::string("scan"));
00023         robotNode.param("map_topic", mMapTopic, std::string("map"));
00024         
00025         ros::NodeHandle mapperNode("~/");
00026         mapperNode.param("grid_resolution", mMapResolution, 0.05);
00027         mapperNode.param("range_threshold", mRangeThreshold, 30.0);
00028         mapperNode.param("map_update_rate", mMapUpdateRate, 1);
00029         mapperNode.param("publish_pose_graph", mPublishPoseGraph, true);
00030         mapperNode.param("max_covariance", mMaxCovariance, 0.05);
00031         mapperNode.param("min_map_size", mMinMapSize, 50);
00032 
00033         // Apply tf_prefix to all used frame-id's
00034         mLaserFrame = mTransformListener.resolve(mLaserFrame);
00035         mRobotFrame = mTransformListener.resolve(mRobotFrame);
00036         mOdometryFrame = mTransformListener.resolve(mOdometryFrame);
00037         mOffsetFrame = mTransformListener.resolve(mOffsetFrame);
00038         mMapFrame = mTransformListener.resolve(mMapFrame);
00039 
00040         // Initialize Publisher/Subscribers
00041         mScanSubscriber = robotNode.subscribe(mScanInputTopic, 100, &MultiMapper::receiveLocalizedScan, this);
00042         mScanPublisher = robotNode.advertise<nav2d_msgs::LocalizedScan>(mScanOutputTopic, 100, true);
00043         mMapServer = robotNode.advertiseService(mMapService, &MultiMapper::getMap, this);
00044         mMapPublisher = robotNode.advertise<nav_msgs::OccupancyGrid>(mMapTopic, 1, true);
00045         mLaserSubscriber = robotNode.subscribe(mLaserTopic, 100, &MultiMapper::receiveLaserScan, this);
00046         mInitialPoseSubscriber = robotNode.subscribe("initialpose", 1, &MultiMapper::receiveInitialPose, this);
00047         mOtherRobotsPublisher = robotNode.advertise<nav2d_msgs::RobotPose>("others", 10, true);
00048 
00049         mVerticesPublisher = mapperNode.advertise<visualization_msgs::Marker>("vertices", 1, true);
00050         mEdgesPublisher = mapperNode.advertise<visualization_msgs::Marker>("edges", 1, true);
00051         mPosePublisher = robotNode.advertise<geometry_msgs::PoseStamped>("localization_result", 1, true);
00052 
00053         // Initialize KARTO-Mapper
00054         mMapper = new karto::OpenMapper(true);
00055         
00056         double param_d;
00057         bool param_b;
00058         int param_i;
00059         
00060         if(mapperNode.getParam("UseScanMatching", param_b))
00061                 mMapper->SetParameters("UseScanMatching", param_b);
00062                 
00063         if(mapperNode.getParam("UseScanBarycenter", param_b))
00064                 mMapper->SetParameters("UseScanBarycenter", param_b);
00065                 
00066         if(mapperNode.getParam("MinimumTravelDistance", param_d))
00067                 mMapper->SetParameters("MinimumTravelDistance", param_d);
00068         
00069         if(mapperNode.getParam("MinimumTravelHeading", param_d))
00070                 mMapper->SetParameters("MinimumTravelHeading", param_d);
00071                 
00072         if(mapperNode.getParam("ScanBufferSize", param_i))
00073                 mMapper->SetParameters("ScanBufferSize", param_i);
00074                 
00075         if(mapperNode.getParam("ScanBufferMaximumScanDistance", param_d))
00076                 mMapper->SetParameters("ScanBufferMaximumScanDistance", param_d);
00077                 
00078         if(mapperNode.getParam("UseResponseExpansion", param_b))
00079                 mMapper->SetParameters("UseResponseExpansion", param_b);
00080                 
00081         if(mapperNode.getParam("DistanceVariancePenalty", param_d))
00082                 mMapper->SetParameters("DistanceVariancePenalty", param_d);
00083                 
00084         if(mapperNode.getParam("MinimumDistancePenalty", param_d))
00085                 mMapper->SetParameters("MinimumDistancePenalty", param_d);
00086                 
00087         if(mapperNode.getParam("AngleVariancePenalty", param_d))
00088                 mMapper->SetParameters("AngleVariancePenalty", param_d);
00089                 
00090         if(mapperNode.getParam("MinimumAnglePenalty", param_d))
00091                 mMapper->SetParameters("MinimumAnglePenalty", param_d);
00092                 
00093         if(mapperNode.getParam("LinkMatchMinimumResponseFine", param_d))
00094                 mMapper->SetParameters("LinkMatchMinimumResponseFine", param_d);
00095                 
00096         if(mapperNode.getParam("LinkScanMaximumDistance", param_d))
00097                 mMapper->SetParameters("LinkScanMaximumDistance", param_d);
00098                 
00099         if(mapperNode.getParam("CorrelationSearchSpaceDimension", param_d))
00100                 mMapper->SetParameters("CorrelationSearchSpaceDimension", param_d);
00101                 
00102         if(mapperNode.getParam("CorrelationSearchSpaceResolution", param_d))
00103                 mMapper->SetParameters("CorrelationSearchSpaceResolution", param_d);
00104                 
00105         if(mapperNode.getParam("CorrelationSearchSpaceSmearDeviation", param_d))
00106                 mMapper->SetParameters("CorrelationSearchSpaceSmearDeviation", param_d);
00107                 
00108         if(mapperNode.getParam("CoarseSearchAngleOffset", param_d))
00109                 mMapper->SetParameters("CoarseSearchAngleOffset", param_d);
00110                 
00111         if(mapperNode.getParam("FineSearchAngleOffset", param_d))
00112                 mMapper->SetParameters("FineSearchAngleOffset", param_d);
00113                 
00114         if(mapperNode.getParam("CoarseAngleResolution", param_d))
00115                 mMapper->SetParameters("CoarseAngleResolution", param_d);
00116                 
00117         if(mapperNode.getParam("LoopSearchSpaceDimension", param_d))
00118                 mMapper->SetParameters("LoopSearchSpaceDimension", param_d);
00119                 
00120         if(mapperNode.getParam("LoopSearchSpaceResolution", param_d))
00121                 mMapper->SetParameters("LoopSearchSpaceResolution", param_d);
00122                 
00123         if(mapperNode.getParam("LoopSearchSpaceSmearDeviation", param_d))
00124                 mMapper->SetParameters("LoopSearchSpaceSmearDeviation", param_d);
00125                 
00126         if(mapperNode.getParam("LoopSearchMaximumDistance", param_d))
00127                 mMapper->SetParameters("LoopSearchMaximumDistance", param_d);
00128                 
00129         if(mapperNode.getParam("LoopMatchMinimumChainSize", param_i))
00130                 mMapper->SetParameters("LoopMatchMinimumChainSize", param_i);
00131                 
00132         if(mapperNode.getParam("LoopMatchMaximumVarianceCoarse", param_d))
00133                 mMapper->SetParameters("LoopMatchMaximumVarianceCoarse", param_d);
00134                 
00135         if(mapperNode.getParam("LoopMatchMinimumResponseCoarse", param_d))
00136                 mMapper->SetParameters("LoopMatchMinimumResponseCoarse", param_d);
00137                 
00138         if(mapperNode.getParam("LoopMatchMinimumResponseFine", param_d))
00139                 mMapper->SetParameters("LoopMatchMinimumResponseFine", param_d);
00140         
00141         mMapper->Message += karto::delegate(this, &MultiMapper::onMessage);
00142         
00143         mLaser = NULL;
00144         
00145         // Initialize Variables
00146         mMapToOdometry.setIdentity();
00147         mOdometryOffset.setIdentity();
00148         mNodesAdded = 0;
00149         mMapChanged = true;
00150         mLastMapUpdate = ros::WallTime(0);
00151         
00152         if(mRobotID == 1)
00153         {
00154                 // I am the number one, so start mapping right away.
00155                 mState = ST_MAPPING;
00156                 ROS_INFO("Inititialized robot 1, starting to map now.");
00157                 mSelfLocalizer = NULL;
00158                 
00159                 geometry_msgs::PoseStamped locResult;
00160                 locResult.header.stamp = ros::Time::now();
00161                 locResult.header.frame_id = mMapFrame.c_str();
00162                 locResult.pose.position.x = 0;
00163                 locResult.pose.position.y = 0;
00164                 locResult.pose.position.z = 0;
00165                 locResult.pose.orientation = tf::createQuaternionMsgFromYaw(0);
00166                 mPosePublisher.publish(locResult);
00167         }else
00168         {
00169                 // I am not number one, so wait to receive a map from number one.
00170                 mState = ST_WAITING_FOR_MAP;
00171                 ROS_INFO("Initialized robot %d, waiting for map from robot 1 now.", mRobotID);
00172                 mSelfLocalizer = new SelfLocalizer();
00173         }
00174 }
00175 
00176 MultiMapper::~MultiMapper()
00177 {
00178 
00179 }
00180 
00181 void MultiMapper::setScanSolver(karto::ScanSolver* scanSolver)
00182 {
00183         mMapper->SetScanSolver(scanSolver);
00184 }
00185 
00186 void MultiMapper::setRobotPose(double x, double y, double yaw)
00187 {
00188         tf::Transform transform;
00189         transform.setOrigin(tf::Vector3(x, y, 0));
00190         transform.setRotation(tf::createQuaternionFromYaw(yaw));
00191         transform = transform.inverse();
00192         
00193         tf::Stamped<tf::Pose> pose_in, pose_out;
00194         pose_in.setData(transform);
00195         pose_in.frame_id_ = mRobotFrame;
00196         pose_in.stamp_ = ros::Time(0);
00197         mTransformListener.transformPose(mOdometryFrame, pose_in, pose_out);
00198         
00199         transform = pose_out;
00200         mOdometryOffset = transform.inverse();
00201 
00202         if(mSelfLocalizer)
00203         {
00204                 delete mSelfLocalizer;
00205                 mSelfLocalizer = NULL;
00206         }
00207         
00208         // Publish the new pose (to inform other nodes, that we are localized now)
00209         geometry_msgs::PoseStamped locResult;
00210         locResult.header.stamp = ros::Time::now();
00211         locResult.header.frame_id = mMapFrame.c_str();
00212         locResult.pose.position.x = x;
00213         locResult.pose.position.y = y;
00214         locResult.pose.position.z = 0;
00215         locResult.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
00216         mPosePublisher.publish(locResult);
00217         
00218         // Publish via tf
00219         mState = ST_MAPPING;
00220         publishTransform();
00221 }
00222 
00223 void MultiMapper::receiveLaserScan(const sensor_msgs::LaserScan::ConstPtr& scan)
00224 {
00225         // Ignore own readings until map has been received
00226         if(mState == ST_WAITING_FOR_MAP)
00227         {
00228                 return;
00229         }
00230         
00231         if(!mLaser)
00232         {
00233                 // Create a laser range finder device and copy in data from the first scan
00234                 char name[10];
00235                 sprintf(name, "robot_%d", mRobotID);
00236 
00237                 // Add the laser to the mapper
00238                 try
00239                 {
00240                         mLaser = karto::LaserRangeFinder::CreateLaserRangeFinder(karto::LaserRangeFinder_Custom, name);         
00241                         mLaser->SetMinimumRange(scan->range_min);
00242                         mLaser->SetMaximumRange(scan->range_max);
00243                         mLaser->SetMinimumAngle(scan->angle_min);
00244                         mLaser->SetMaximumAngle(scan->angle_max);
00245                         mLaser->SetAngularResolution(scan->angle_increment);
00246                         mLaser->SetRangeThreshold(mRangeThreshold);
00247                         mMapper->Process(mLaser);
00248                 }
00249                 catch(karto::Exception e)
00250                 {
00251                         ROS_ERROR("Could not add new Laser to Mapper: %s", e.GetErrorMessage().ToCString());
00252                         return;
00253                 }
00254         }
00255         
00256         if(mState == ST_LOCALIZING)
00257         {
00258                 mSelfLocalizer->process(scan);
00259                 if(mSelfLocalizer->getCovariance() < mMaxCovariance)
00260                 {
00261                         // Localization finished, kill the localizer and start mapping
00262                         ROS_INFO("Localization finished on robot %d, now starting to map.", mRobotID);
00263                         tf::Transform p = mSelfLocalizer->getBestPose();
00264                         setRobotPose(p.getOrigin().getX(), p.getOrigin().getY(), tf::getYaw(p.getRotation()));
00265                 }
00266         }else 
00267         if(mState == ST_MAPPING)
00268         {
00269                 // get the odometry pose from tf
00270                 tf::StampedTransform tfPose;
00271                 try
00272                 {
00273                         mTransformListener.lookupTransform(mOffsetFrame, mLaserFrame, scan->header.stamp, tfPose);
00274                 }
00275                 catch(tf::TransformException e)
00276                 {
00277                         try
00278                         {
00279                                 mTransformListener.lookupTransform(mOffsetFrame, mLaserFrame, ros::Time(0), tfPose);
00280                         }
00281                         catch(tf::TransformException e)
00282                         {
00283                                 ROS_WARN("Failed to compute odometry pose, skipping scan (%s)", e.what());
00284                                 return;
00285                         }
00286                 }
00287                 karto::Pose2 kartoPose = karto::Pose2(tfPose.getOrigin().x(), tfPose.getOrigin().y(), tf::getYaw(tfPose.getRotation()));
00288                 
00289                 // create localized range scan
00290                 karto::RangeReadingsList readings;
00291                 std::vector<float>::const_iterator it;
00292                 for(it = scan->ranges.begin(); it != scan->ranges.end(); it++)
00293                 {
00294                         if(*it == 0)
00295                                 readings.Add(scan->range_max);
00296                         else    
00297                                 readings.Add(*it);
00298                 }
00299 
00300                 karto::LocalizedLaserScanPtr laserScan =
00301                         new karto::LocalizedRangeScan(mLaser->GetIdentifier(), readings);
00302 
00303                 laserScan->SetOdometricPose(kartoPose);
00304                 laserScan->SetCorrectedPose(kartoPose);
00305                 
00306                 bool success;
00307                 try
00308                 {
00309                         success = mMapper->Process(laserScan);
00310                 }
00311                 catch(karto::Exception e)
00312                 {
00313                         ROS_ERROR("%s", e.GetErrorMessage().ToCString());
00314                         success = false;
00315                 }
00316                 
00317                 if(success)
00318                 {
00319                         // Compute the map->odom transform
00320                         karto::Pose2 corrected_pose = laserScan->GetCorrectedPose();
00321                         tf::Pose map_in_robot(tf::createQuaternionFromYaw(corrected_pose.GetHeading()), tf::Vector3(corrected_pose.GetX(), corrected_pose.GetY(), 0.0));
00322                         map_in_robot = map_in_robot.inverse();
00323                         tf::Stamped<tf::Pose> map_in_odom;
00324                         bool ok = true;
00325                         try
00326                         {
00327                                 mTransformListener.transformPose(mOffsetFrame, tf::Stamped<tf::Pose>(map_in_robot, ros::Time(0) /*scan->header.stamp*/, mLaserFrame), map_in_odom);
00328                         }
00329                         catch(tf::TransformException e)
00330                         {
00331                                 ROS_WARN("Transform from %s to %s failed! (%s)", mLaserFrame.c_str(), mOffsetFrame.c_str(), e.what());
00332                                 ok = false;
00333                         }
00334                         if(ok) 
00335                         {
00336                                 mMapToOdometry = tf::Transform(tf::Quaternion( map_in_odom.getRotation() ), tf::Point(map_in_odom.getOrigin() ) ).inverse();
00337                                 tf::Vector3 v = mMapToOdometry.getOrigin();
00338                                 v.setZ(0);
00339                                 mMapToOdometry.setOrigin(v);
00340                         }
00341                         mNodesAdded++;
00342                         mMapChanged = true;
00343 
00344                         ros::WallDuration d = ros::WallTime::now() - mLastMapUpdate;
00345                         if(mMapUpdateRate > 0 && d.toSec() > mMapUpdateRate)
00346                         {
00347                                 sendMap();
00348                         }
00349 
00350                         // Send the scan to the other robots via com-layer (DDS)
00351                         ROS_DEBUG("Robot %d: Sending scan (uniqueID: %d, Sensor: %s, stateID: %d)", mRobotID, laserScan->GetUniqueId(), laserScan->GetSensorIdentifier().ToString().ToCString(), laserScan->GetStateId());
00352                         sendLocalizedScan(scan, laserScan->GetOdometricPose());
00353                         
00354                         // Publish via extra topic
00355                         nav2d_msgs::RobotPose other;
00356                         other.header.stamp = ros::Time::now();
00357                         other.header.frame_id = mMapFrame;
00358                         other.robot_id = mRobotID;
00359                         other.pose.x = laserScan->GetCorrectedPose().GetX();
00360                         other.pose.y = laserScan->GetCorrectedPose().GetY();
00361                         other.pose.theta = laserScan->GetCorrectedPose().GetHeading();
00362                         mOtherRobotsPublisher.publish(other);
00363                 }
00364         }
00365 }
00366 
00367 bool MultiMapper::getMap(nav_msgs::GetMap::Request  &req, nav_msgs::GetMap::Response &res)
00368 {
00369         if(mState == ST_WAITING_FOR_MAP && mNodesAdded < mMinMapSize)
00370         {
00371                 ROS_INFO("Still waiting for map from robot 1.");
00372                 return false;
00373         }
00374         
00375         if(sendMap())
00376         {
00377                 res.map = mGridMap;
00378                 return true;
00379         }else
00380         {
00381                 ROS_WARN("Serving map request failed!");
00382                 return false;
00383         }
00384 }
00385 
00386 bool MultiMapper::sendMap()
00387 {
00388         if(!updateMap()) return false;
00389         
00390         // Publish the map
00391         mMapPublisher.publish(mGridMap);
00392         mLastMapUpdate = ros::WallTime::now();
00393 
00394         // Publish the pose-graph
00395         if(mPublishPoseGraph)
00396         {
00397                 // Publish the vertices
00398                 karto::MapperGraph::VertexList vertices = mMapper->GetGraph()->GetVertices();
00399                 visualization_msgs::Marker marker;
00400                 marker.header.frame_id = mMapFrame;
00401                 marker.header.stamp = ros::Time();
00402                 marker.id = 0;
00403                 marker.type = visualization_msgs::Marker::SPHERE_LIST;
00404                 marker.action = visualization_msgs::Marker::ADD;
00405                 marker.pose.position.x = 0;
00406                 marker.pose.position.y = 0;
00407                 marker.pose.position.z = 0;
00408                 marker.pose.orientation.x = 0.0;
00409                 marker.pose.orientation.y = 0.0;
00410                 marker.pose.orientation.z = 0.0;
00411                 marker.pose.orientation.w = 1.0;
00412                 marker.scale.x = 0.1;
00413                 marker.scale.y = 0.1;
00414                 marker.scale.z = 0.1;
00415                 marker.color.a = 1.0;
00416                 marker.color.r = 0.0;
00417                 marker.color.g = 1.0;
00418                 marker.color.b = 0.0;
00419                 marker.points.resize(vertices.Size());
00420                 
00421                 for(int i = 0; i < vertices.Size(); i++)
00422                 {
00423                         marker.points[i].x = vertices[i]->GetVertexObject()->GetCorrectedPose().GetX();
00424                         marker.points[i].y = vertices[i]->GetVertexObject()->GetCorrectedPose().GetY();
00425                         marker.points[i].z = 0;
00426                 }
00427                 mVerticesPublisher.publish(marker);
00428                 
00429                 // Publish the edges
00430                 karto::MapperGraph::EdgeList edges = mMapper->GetGraph()->GetEdges();
00431                 marker.header.frame_id = mMapFrame;
00432                 marker.header.stamp = ros::Time();
00433                 marker.id = 0;
00434                 marker.type = visualization_msgs::Marker::LINE_LIST;
00435                 marker.scale.x = 0.01;
00436                 marker.color.a = 1.0;
00437                 marker.color.r = 1.0;
00438                 marker.color.g = 0.0;
00439                 marker.color.b = 0.0;
00440                 marker.points.resize(edges.Size() * 2);
00441                 
00442                 for(int i = 0; i < edges.Size(); i++)
00443                 {
00444                         marker.points[2*i].x = edges[i]->GetSource()->GetVertexObject()->GetCorrectedPose().GetX();
00445                         marker.points[2*i].y = edges[i]->GetSource()->GetVertexObject()->GetCorrectedPose().GetY();
00446                         marker.points[2*i].z = 0;
00447 
00448                         marker.points[2*i+1].x = edges[i]->GetTarget()->GetVertexObject()->GetCorrectedPose().GetX();
00449                         marker.points[2*i+1].y = edges[i]->GetTarget()->GetVertexObject()->GetCorrectedPose().GetY();
00450                         marker.points[2*i+1].z = 0;
00451                 }
00452                 mEdgesPublisher.publish(marker);
00453         }
00454         return true;
00455 }
00456 
00457 bool MultiMapper::updateMap()
00458 {
00459         if(!mMapChanged) return true;
00460         
00461         const karto::LocalizedLaserScanList allScans = mMapper->GetAllProcessedScans();
00462         karto::OccupancyGridPtr kartoGrid = karto::OccupancyGrid::CreateFromScans(allScans, mMapResolution);
00463 
00464         if(!kartoGrid)
00465         {
00466                 ROS_WARN("Failed to get occupancy map from Karto-Mapper.");
00467                 return false; 
00468         }
00469 
00470         // Translate to ROS format
00471         unsigned int width = kartoGrid->GetWidth();
00472         unsigned int height = kartoGrid->GetHeight();
00473         karto::Vector2<kt_double> offset = kartoGrid->GetCoordinateConverter()->GetOffset();
00474 
00475         if(     mGridMap.info.width != width || 
00476                 mGridMap.info.height != height || 
00477                 mGridMap.info.origin.position.x != offset.GetX() || 
00478                 mGridMap.info.origin.position.y != offset.GetY())
00479         {
00480                 mGridMap.info.resolution = mMapResolution;
00481                 mGridMap.info.origin.position.x = offset.GetX();
00482                 mGridMap.info.origin.position.y = offset.GetY();
00483                 mGridMap.info.width = width;
00484                 mGridMap.info.height = height;
00485                 mGridMap.data.resize(mGridMap.info.width * mGridMap.info.height);
00486         }
00487         
00488         for (unsigned int y = 0; y < height; y++)
00489         {
00490                 for (unsigned int x = 0; x < width; x++) 
00491                 {
00492                         // Getting the value at position x,y
00493                         kt_int8u value = kartoGrid->GetValue(karto::Vector2<kt_int32s>(x, y));
00494 
00495                         switch (value)
00496                         {
00497                         case karto::GridStates_Unknown:
00498                                 mGridMap.data[MAP_IDX(mGridMap.info.width, x, y)] = -1;
00499                                 break;
00500                         case karto::GridStates_Occupied:
00501                                 mGridMap.data[MAP_IDX(mGridMap.info.width, x, y)] = 100;
00502                                 break;
00503                         case karto::GridStates_Free:
00504                                 mGridMap.data[MAP_IDX(mGridMap.info.width, x, y)] = 0;
00505                                 break;
00506                         default:
00507                                 ROS_WARN("Encountered unknown cell value at %d, %d", x, y);
00508                                 break;
00509                         }
00510                 }
00511         }
00512 
00513         // Set the header information on the map
00514         mGridMap.header.stamp = ros::Time::now();
00515         mGridMap.header.frame_id = mMapFrame.c_str();
00516         mMapChanged = false;
00517         return true;
00518 }
00519 
00520 void MultiMapper::receiveLocalizedScan(const nav2d_msgs::LocalizedScan::ConstPtr& scan)
00521 {
00522         // Ignore my own scans
00523         if(scan->robot_id == mRobotID) return;
00524         
00525         // Get the robot id
00526         char robot[10];
00527         sprintf(robot, "robot_%d", scan->robot_id);
00528         
00529         // Get the scan pose
00530         karto::Pose2 scanPose(scan->x, scan->y, scan->yaw);
00531         
00532         // Get the scan readings
00533         karto::RangeReadingsList readings;
00534         std::vector<float>::const_iterator it;
00535         for(it = scan->scan.ranges.begin(); it != scan->scan.ranges.end(); it++)
00536         {
00537                 if(*it == 0)
00538                         readings.Add(scan->scan.range_max);
00539                 else    
00540                         readings.Add(*it);
00541         }
00542         
00543         // create localized laser scan
00544         karto::LocalizedLaserScanPtr localizedScan =
00545                 new karto::LocalizedRangeScan(robot, readings);
00546 
00547         localizedScan->SetOdometricPose(scanPose);
00548         localizedScan->SetCorrectedPose(scanPose);
00549         
00550         // feed the localized scan to the Karto-Mapper
00551         bool added = false;
00552         try
00553         {
00554                 added = mMapper->Process(localizedScan);
00555         }
00556         catch(karto::Exception e1)
00557         {
00558                 if(mOtherLasers.find(scan->robot_id) == mOtherLasers.end())
00559                 {
00560                         try
00561                         {
00562                                 karto::LaserRangeFinderPtr laser = karto::LaserRangeFinder::CreateLaserRangeFinder(karto::LaserRangeFinder_Custom, robot);
00563                                 laser->SetMinimumRange(scan->scan.range_min);
00564                                 laser->SetMaximumRange(scan->scan.range_max);
00565                                 laser->SetMinimumAngle(scan->scan.angle_min);
00566                                 laser->SetMaximumAngle(scan->scan.angle_max);
00567                                 laser->SetAngularResolution(scan->scan.angle_increment);
00568                                 laser->SetRangeThreshold(mRangeThreshold);
00569                                 mMapper->Process(laser);
00570                                 mOtherLasers.insert(std::pair<int,karto::LaserRangeFinderPtr>(scan->robot_id,laser));
00571                         
00572                                 added = mMapper->Process(localizedScan);
00573                         }
00574                         catch(karto::Exception e2)
00575                         {
00576                                 ROS_ERROR("%s", e2.GetErrorMessage().ToCString());
00577                         }
00578                 }else
00579                 {
00580                         ROS_ERROR("%s", e1.GetErrorMessage().ToCString());
00581                 }
00582         }
00583         if(added)
00584         {
00585                 mNodesAdded++;
00586                 mMapChanged = true;
00587                 ROS_DEBUG("Robot %d: Received scan (uniqueID: %d, Sensor: %s, stateID: %d)", mRobotID, localizedScan->GetUniqueId(), localizedScan->GetSensorIdentifier().ToString().ToCString(), localizedScan->GetStateId());
00588                 
00589                 // Publish via extra topic
00590                 nav2d_msgs::RobotPose other;
00591                 other.header.stamp = ros::Time::now();
00592                 other.header.frame_id = mMapFrame;
00593                 other.robot_id = scan->robot_id;
00594                 other.pose.x = localizedScan->GetCorrectedPose().GetX();
00595                 other.pose.y = localizedScan->GetCorrectedPose().GetY();
00596                 other.pose.theta = localizedScan->GetCorrectedPose().GetHeading();
00597                 mOtherRobotsPublisher.publish(other);
00598                 
00599                 // Send the map via topic
00600                 ros::WallDuration d = ros::WallTime::now() - mLastMapUpdate;
00601                 if(mMapUpdateRate > 0 && d.toSec() > mMapUpdateRate)
00602                 {
00603                         sendMap();
00604                         if(mState == ST_LOCALIZING)
00605                         {
00606                                 mSelfLocalizer->convertMap(mGridMap);
00607                         }
00608                 }
00609         }else
00610         {
00611                 ROS_DEBUG("Discarded Scan from Robot %d!", scan->robot_id);
00612         }
00613 
00614         if(mState == ST_WAITING_FOR_MAP && mNodesAdded >= mMinMapSize)
00615         {
00616                 sendMap();
00617                 mSelfLocalizer->convertMap(mGridMap);
00618                 mSelfLocalizer->initialize();
00619                 mState = ST_LOCALIZING;
00620                 ROS_INFO("Received a map, now starting to localize.");
00621                 mSelfLocalizer->publishParticleCloud();
00622         }
00623 }
00624 
00625 void MultiMapper::sendLocalizedScan(const sensor_msgs::LaserScan::ConstPtr& scan, const karto::Pose2& pose)
00626 {
00627         nav2d_msgs::LocalizedScan rosScan;
00628         rosScan.robot_id = mRobotID;
00629         rosScan.laser_type = 0;
00630         rosScan.x = pose.GetX();
00631         rosScan.y = pose.GetY();
00632         rosScan.yaw = pose.GetHeading();
00633         
00634         rosScan.scan.angle_min = scan->angle_min;
00635         rosScan.scan.angle_max = scan->angle_max;
00636         rosScan.scan.range_min = scan->range_min;
00637         rosScan.scan.range_max = scan->range_max;
00638         rosScan.scan.angle_increment = scan->angle_increment;
00639         rosScan.scan.time_increment = scan->time_increment;
00640         rosScan.scan.scan_time = scan->scan_time;
00641         
00642         unsigned int nReadings = scan->ranges.size();
00643         rosScan.scan.ranges.resize(nReadings);
00644         for(unsigned int i = 0; i < nReadings; i++)
00645         {
00646                 rosScan.scan.ranges[i] = scan->ranges[i];
00647         }
00648 
00649 //      rosScan.scan = *scan;
00650         mScanPublisher.publish(rosScan);
00651 }
00652 
00653 void MultiMapper::receiveInitialPose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& pose)
00654 {
00655         double x = pose->pose.pose.position.x;
00656         double y = pose->pose.pose.position.y;
00657         double yaw = tf::getYaw(pose->pose.pose.orientation);
00658         ROS_INFO("Received initial pose (%.2f, %.2f, %.2f) on robot %d, now starting to map.",x,y,yaw,mRobotID);
00659         try
00660         {
00661                 setRobotPose(x,y,yaw);
00662         }
00663         catch(tf::TransformException e)
00664         {
00665                 ROS_ERROR("Failed to set pose on robot %d! (%s)", mRobotID, e.what());
00666                 return;
00667         }
00668 }
00669 
00670 void MultiMapper::onMessage(const void* sender, karto::MapperEventArguments& args)
00671 {
00672         ROS_DEBUG("OpenMapper: %s\n", args.GetEventMessage().ToCString());
00673 }
00674 
00675 void MultiMapper::publishTransform()
00676 {
00677         if(mState == ST_MAPPING)
00678         {
00679                 mTransformBroadcaster.sendTransform(tf::StampedTransform (mOdometryOffset, ros::Time::now() , mOffsetFrame, mOdometryFrame));
00680                 mTransformBroadcaster.sendTransform(tf::StampedTransform (mMapToOdometry, ros::Time::now() , mMapFrame, mOffsetFrame));
00681         }
00682 }


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Thu Aug 27 2015 14:07:25