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


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Mon Oct 6 2014 02:44:17