$search
00001 /* 00002 * slam_gmapping 00003 * Copyright (c) 2008, Willow Garage, Inc. 00004 * 00005 * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE 00006 * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY 00007 * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS 00008 * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED. 00009 * 00010 * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO 00011 * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS 00012 * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND 00013 * CONDITIONS. 00014 * 00015 */ 00016 00017 /* Author: Brian Gerkey */ 00018 /* Modified by: Charles DuHadway */ 00019 00020 00107 #include "slam_gmapping.h" 00108 00109 #include <iostream> 00110 00111 #include <time.h> 00112 00113 #include "ros/ros.h" 00114 #include "ros/console.h" 00115 #include "nav_msgs/MapMetaData.h" 00116 00117 #include "gmapping/sensor/sensor_range/rangesensor.h" 00118 #include "gmapping/sensor/sensor_odometry/odometrysensor.h" 00119 00120 // compute linear index for given map coords 00121 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) 00122 00123 SlamGMapping::SlamGMapping(): 00124 map_to_odom_(tf::Transform(tf::createQuaternionFromRPY( 0, 0, 0 ), tf::Point(0, 0, 0 ))), 00125 laser_count_(0), transform_thread_(NULL) 00126 { 00127 // log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->setLevel(ros::console::g_level_lookup[ros::console::levels::Debug]); 00128 00129 // The library is pretty chatty 00130 //gsp_ = new GMapping::GridSlamProcessor(std::cerr); 00131 gsp_ = new GMapping::GridSlamProcessor(); 00132 ROS_ASSERT(gsp_); 00133 00134 tfB_ = new tf::TransformBroadcaster(); 00135 ROS_ASSERT(tfB_); 00136 00137 gsp_laser_ = NULL; 00138 gsp_laser_angle_increment_ = 0.0; 00139 gsp_odom_ = NULL; 00140 00141 got_first_scan_ = false; 00142 got_map_ = false; 00143 00144 ros::NodeHandle private_nh_("~"); 00145 00146 // Parameters used by our GMapping wrapper 00147 if(!private_nh_.getParam("throttle_scans", throttle_scans_)) 00148 throttle_scans_ = 1; 00149 if(!private_nh_.getParam("base_frame", base_frame_)) 00150 base_frame_ = "base_link"; 00151 if(!private_nh_.getParam("map_frame", map_frame_)) 00152 map_frame_ = "map"; 00153 if(!private_nh_.getParam("odom_frame", odom_frame_)) 00154 odom_frame_ = "odom"; 00155 00156 double transform_publish_period; 00157 private_nh_.param("transform_publish_period", transform_publish_period, 0.05); 00158 00159 double tmp; 00160 if(!private_nh_.getParam("map_update_interval", tmp)) 00161 tmp = 5.0; 00162 map_update_interval_.fromSec(tmp); 00163 00164 // Parameters used by GMapping itself 00165 maxUrange_ = 0.0; maxRange_ = 0.0; // preliminary default, will be set in initMapper() 00166 if(!private_nh_.getParam("sigma", sigma_)) 00167 sigma_ = 0.05; 00168 if(!private_nh_.getParam("kernelSize", kernelSize_)) 00169 kernelSize_ = 1; 00170 if(!private_nh_.getParam("lstep", lstep_)) 00171 lstep_ = 0.05; 00172 if(!private_nh_.getParam("astep", astep_)) 00173 astep_ = 0.05; 00174 if(!private_nh_.getParam("iterations", iterations_)) 00175 iterations_ = 5; 00176 if(!private_nh_.getParam("lsigma", lsigma_)) 00177 lsigma_ = 0.075; 00178 if(!private_nh_.getParam("ogain", ogain_)) 00179 ogain_ = 3.0; 00180 if(!private_nh_.getParam("lskip", lskip_)) 00181 lskip_ = 0; 00182 if(!private_nh_.getParam("srr", srr_)) 00183 srr_ = 0.1; 00184 if(!private_nh_.getParam("srt", srt_)) 00185 srt_ = 0.2; 00186 if(!private_nh_.getParam("str", str_)) 00187 str_ = 0.1; 00188 if(!private_nh_.getParam("stt", stt_)) 00189 stt_ = 0.2; 00190 if(!private_nh_.getParam("linearUpdate", linearUpdate_)) 00191 linearUpdate_ = 1.0; 00192 if(!private_nh_.getParam("angularUpdate", angularUpdate_)) 00193 angularUpdate_ = 0.5; 00194 if(!private_nh_.getParam("temporalUpdate", temporalUpdate_)) 00195 temporalUpdate_ = -1.0; 00196 if(!private_nh_.getParam("resampleThreshold", resampleThreshold_)) 00197 resampleThreshold_ = 0.5; 00198 if(!private_nh_.getParam("particles", particles_)) 00199 particles_ = 30; 00200 if(!private_nh_.getParam("xmin", xmin_)) 00201 xmin_ = -100.0; 00202 if(!private_nh_.getParam("ymin", ymin_)) 00203 ymin_ = -100.0; 00204 if(!private_nh_.getParam("xmax", xmax_)) 00205 xmax_ = 100.0; 00206 if(!private_nh_.getParam("ymax", ymax_)) 00207 ymax_ = 100.0; 00208 if(!private_nh_.getParam("delta", delta_)) 00209 delta_ = 0.05; 00210 if(!private_nh_.getParam("occ_thresh", occ_thresh_)) 00211 occ_thresh_ = 0.25; 00212 if(!private_nh_.getParam("llsamplerange", llsamplerange_)) 00213 llsamplerange_ = 0.01; 00214 if(!private_nh_.getParam("llsamplestep", llsamplestep_)) 00215 llsamplestep_ = 0.01; 00216 if(!private_nh_.getParam("lasamplerange", lasamplerange_)) 00217 lasamplerange_ = 0.005; 00218 if(!private_nh_.getParam("lasamplestep", lasamplestep_)) 00219 lasamplestep_ = 0.005; 00220 00221 entropy_publisher_ = private_nh_.advertise<std_msgs::Float64>("entropy", 1, true); 00222 sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true); 00223 sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true); 00224 ss_ = node_.advertiseService("dynamic_map", &SlamGMapping::mapCallback, this); 00225 scan_filter_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(node_, "scan", 5); 00226 scan_filter_ = new tf::MessageFilter<sensor_msgs::LaserScan>(*scan_filter_sub_, tf_, odom_frame_, 5); 00227 scan_filter_->registerCallback(boost::bind(&SlamGMapping::laserCallback, this, _1)); 00228 00229 transform_thread_ = new boost::thread(boost::bind(&SlamGMapping::publishLoop, this, transform_publish_period)); 00230 } 00231 00232 void SlamGMapping::publishLoop(double transform_publish_period){ 00233 if(transform_publish_period == 0) 00234 return; 00235 00236 ros::Rate r(1.0 / transform_publish_period); 00237 while(ros::ok()){ 00238 publishTransform(); 00239 r.sleep(); 00240 } 00241 } 00242 00243 SlamGMapping::~SlamGMapping() 00244 { 00245 if(transform_thread_){ 00246 transform_thread_->join(); 00247 delete transform_thread_; 00248 } 00249 00250 delete gsp_; 00251 if(gsp_laser_) 00252 delete gsp_laser_; 00253 if(gsp_odom_) 00254 delete gsp_odom_; 00255 if (scan_filter_) 00256 delete scan_filter_; 00257 if (scan_filter_sub_) 00258 delete scan_filter_sub_; 00259 } 00260 00261 bool 00262 SlamGMapping::getOdomPose(GMapping::OrientedPoint& gmap_pose, const ros::Time& t) 00263 { 00264 // Get the robot's pose 00265 tf::Stamped<tf::Pose> ident (tf::Transform(tf::createQuaternionFromRPY(0,0,0), 00266 tf::Vector3(0,0,0)), t, base_frame_); 00267 tf::Stamped<tf::Transform> odom_pose; 00268 try 00269 { 00270 tf_.transformPose(odom_frame_, ident, odom_pose); 00271 } 00272 catch(tf::TransformException e) 00273 { 00274 ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what()); 00275 return false; 00276 } 00277 double yaw = tf::getYaw(odom_pose.getRotation()); 00278 00279 gmap_pose = GMapping::OrientedPoint(odom_pose.getOrigin().x(), 00280 odom_pose.getOrigin().y(), 00281 yaw); 00282 return true; 00283 } 00284 00285 bool 00286 SlamGMapping::initMapper(const sensor_msgs::LaserScan& scan) 00287 { 00288 // Get the laser's pose, relative to base. 00289 tf::Stamped<tf::Pose> ident; 00290 tf::Stamped<tf::Transform> laser_pose; 00291 ident.setIdentity(); 00292 ident.frame_id_ = scan.header.frame_id; 00293 ident.stamp_ = scan.header.stamp; 00294 try 00295 { 00296 tf_.transformPose(base_frame_, ident, laser_pose); 00297 } 00298 catch(tf::TransformException e) 00299 { 00300 ROS_WARN("Failed to compute laser pose, aborting initialization (%s)", 00301 e.what()); 00302 return false; 00303 } 00304 00305 double yaw = tf::getYaw(laser_pose.getRotation()); 00306 00307 GMapping::OrientedPoint gmap_pose(laser_pose.getOrigin().x(), 00308 laser_pose.getOrigin().y(), 00309 yaw); 00310 ROS_DEBUG("laser's pose wrt base: %.3f %.3f %.3f", 00311 laser_pose.getOrigin().x(), 00312 laser_pose.getOrigin().y(), 00313 yaw); 00314 00315 // To account for lasers that are mounted upside-down, we determine the 00316 // min, max, and increment angles of the laser in the base frame. 00317 tf::Quaternion q; 00318 q.setRPY(0.0, 0.0, scan.angle_min); 00319 tf::Stamped<tf::Quaternion> min_q(q, scan.header.stamp, 00320 scan.header.frame_id); 00321 q.setRPY(0.0, 0.0, scan.angle_max); 00322 tf::Stamped<tf::Quaternion> max_q(q, scan.header.stamp, 00323 scan.header.frame_id); 00324 try 00325 { 00326 tf_.transformQuaternion(base_frame_, min_q, min_q); 00327 tf_.transformQuaternion(base_frame_, max_q, max_q); 00328 } 00329 catch(tf::TransformException& e) 00330 { 00331 ROS_WARN("Unable to transform min/max laser angles into base frame: %s", 00332 e.what()); 00333 return false; 00334 } 00335 00336 gsp_laser_beam_count_ = scan.ranges.size(); 00337 00338 double angle_min = tf::getYaw(min_q); 00339 double angle_max = tf::getYaw(max_q); 00340 gsp_laser_angle_increment_ = scan.angle_increment; 00341 ROS_DEBUG("Laser angles in base frame: min: %.3f max: %.3f inc: %.3f", angle_min, angle_max, gsp_laser_angle_increment_); 00342 00343 // setting maxRange and maxUrange here so we can set a reasonable default 00344 ros::NodeHandle private_nh_("~"); 00345 if(!private_nh_.getParam("maxRange", maxRange_)) 00346 maxRange_ = scan.range_max - 0.01; 00347 if(!private_nh_.getParam("maxUrange", maxUrange_)) 00348 maxUrange_ = maxRange_; 00349 00350 // The laser must be called "FLASER". 00351 // We pass in the absolute value of the computed angle increment, on the 00352 // assumption that GMapping requires a positive angle increment. If the 00353 // actual increment is negative, we'll swap the order of ranges before 00354 // feeding each scan to GMapping. 00355 gsp_laser_ = new GMapping::RangeSensor("FLASER", 00356 gsp_laser_beam_count_, 00357 fabs(gsp_laser_angle_increment_), 00358 gmap_pose, 00359 0.0, 00360 maxRange_); 00361 ROS_ASSERT(gsp_laser_); 00362 00363 GMapping::SensorMap smap; 00364 smap.insert(make_pair(gsp_laser_->getName(), gsp_laser_)); 00365 gsp_->setSensorMap(smap); 00366 00367 gsp_odom_ = new GMapping::OdometrySensor(odom_frame_); 00368 ROS_ASSERT(gsp_odom_); 00369 00370 00372 GMapping::OrientedPoint initialPose; 00373 if(!getOdomPose(initialPose, scan.header.stamp)) 00374 initialPose = GMapping::OrientedPoint(0.0, 0.0, 0.0); 00375 00376 gsp_->setMatchingParameters(maxUrange_, maxRange_, sigma_, 00377 kernelSize_, lstep_, astep_, iterations_, 00378 lsigma_, ogain_, lskip_); 00379 00380 gsp_->setMotionModelParameters(srr_, srt_, str_, stt_); 00381 gsp_->setUpdateDistances(linearUpdate_, angularUpdate_, resampleThreshold_); 00382 gsp_->setUpdatePeriod(temporalUpdate_); 00383 gsp_->setgenerateMap(false); 00384 gsp_->GridSlamProcessor::init(particles_, xmin_, ymin_, xmax_, ymax_, 00385 delta_, initialPose); 00386 gsp_->setllsamplerange(llsamplerange_); 00387 gsp_->setllsamplestep(llsamplestep_); 00391 gsp_->setlasamplerange(lasamplerange_); 00392 gsp_->setlasamplestep(lasamplestep_); 00393 00394 // Call the sampling function once to set the seed. 00395 GMapping::sampleGaussian(1,time(NULL)); 00396 00397 ROS_INFO("Initialization complete"); 00398 00399 return true; 00400 } 00401 00402 bool 00403 SlamGMapping::addScan(const sensor_msgs::LaserScan& scan, GMapping::OrientedPoint& gmap_pose) 00404 { 00405 if(!getOdomPose(gmap_pose, scan.header.stamp)) 00406 return false; 00407 00408 if(scan.ranges.size() != gsp_laser_beam_count_) 00409 return false; 00410 00411 // GMapping wants an array of doubles... 00412 double* ranges_double = new double[scan.ranges.size()]; 00413 // If the angle increment is negative, then we conclude that the laser is 00414 // upside down, and invert the order of the readings. 00415 if (gsp_laser_angle_increment_ < 0) 00416 { 00417 ROS_DEBUG("Inverting scan"); 00418 int num_ranges = scan.ranges.size(); 00419 for(int i=0; i < num_ranges; i++) 00420 { 00421 // Must filter out short readings, because the mapper won't 00422 if(scan.ranges[i] < scan.range_min) 00423 ranges_double[i] = (double)scan.range_max; 00424 else 00425 ranges_double[i] = (double)scan.ranges[num_ranges - i - 1]; 00426 } 00427 } else 00428 { 00429 for(unsigned int i=0; i < scan.ranges.size(); i++) 00430 { 00431 // Must filter out short readings, because the mapper won't 00432 if(scan.ranges[i] < scan.range_min) 00433 ranges_double[i] = (double)scan.range_max; 00434 else 00435 ranges_double[i] = (double)scan.ranges[i]; 00436 } 00437 } 00438 00439 GMapping::RangeReading reading(scan.ranges.size(), 00440 ranges_double, 00441 gsp_laser_, 00442 scan.header.stamp.toSec()); 00443 00444 // ...but it deep copies them in RangeReading constructor, so we don't 00445 // need to keep our array around. 00446 delete[] ranges_double; 00447 00448 reading.setPose(gmap_pose); 00449 00450 /* 00451 ROS_DEBUG("scanpose (%.3f): %.3f %.3f %.3f\n", 00452 scan.header.stamp.toSec(), 00453 gmap_pose.x, 00454 gmap_pose.y, 00455 gmap_pose.theta); 00456 */ 00457 00458 return gsp_->processScan(reading); 00459 } 00460 00461 void 00462 SlamGMapping::laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan) 00463 { 00464 laser_count_++; 00465 if ((laser_count_ % throttle_scans_) != 0) 00466 return; 00467 00468 static ros::Time last_map_update(0,0); 00469 00470 // We can't initialize the mapper until we've got the first scan 00471 if(!got_first_scan_) 00472 { 00473 if(!initMapper(*scan)) 00474 return; 00475 got_first_scan_ = true; 00476 } 00477 00478 GMapping::OrientedPoint odom_pose; 00479 if(addScan(*scan, odom_pose)) 00480 { 00481 ROS_DEBUG("scan processed"); 00482 00483 GMapping::OrientedPoint mpose = gsp_->getParticles()[gsp_->getBestParticleIndex()].pose; 00484 ROS_DEBUG("new best pose: %.3f %.3f %.3f", mpose.x, mpose.y, mpose.theta); 00485 ROS_DEBUG("odom pose: %.3f %.3f %.3f", odom_pose.x, odom_pose.y, odom_pose.theta); 00486 ROS_DEBUG("correction: %.3f %.3f %.3f", mpose.x - odom_pose.x, mpose.y - odom_pose.y, mpose.theta - odom_pose.theta); 00487 00488 tf::Stamped<tf::Pose> odom_to_map; 00489 try 00490 { 00491 tf_.transformPose(odom_frame_,tf::Stamped<tf::Pose> (tf::Transform(tf::createQuaternionFromRPY(0, 0, mpose.theta), 00492 tf::Vector3(mpose.x, mpose.y, 0.0)).inverse(), 00493 scan->header.stamp, base_frame_),odom_to_map); 00494 } 00495 catch(tf::TransformException e){ 00496 ROS_ERROR("Transform from base_link to odom failed\n"); 00497 odom_to_map.setIdentity(); 00498 } 00499 00500 map_to_odom_mutex_.lock(); 00501 map_to_odom_ = tf::Transform(tf::Quaternion( odom_to_map.getRotation() ), 00502 tf::Point( odom_to_map.getOrigin() ) ).inverse(); 00503 map_to_odom_mutex_.unlock(); 00504 00505 if(!got_map_ || (scan->header.stamp - last_map_update) > map_update_interval_) 00506 { 00507 updateMap(*scan); 00508 last_map_update = scan->header.stamp; 00509 ROS_DEBUG("Updated the map"); 00510 } 00511 } 00512 } 00513 00514 double 00515 SlamGMapping::computePoseEntropy() 00516 { 00517 double weight_total=0.0; 00518 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it = gsp_->getParticles().begin(); 00519 it != gsp_->getParticles().end(); 00520 ++it) 00521 { 00522 weight_total += it->weight; 00523 } 00524 double entropy = 0.0; 00525 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it = gsp_->getParticles().begin(); 00526 it != gsp_->getParticles().end(); 00527 ++it) 00528 { 00529 if(it->weight/weight_total > 0.0) 00530 entropy += it->weight/weight_total * log(it->weight/weight_total); 00531 } 00532 return -entropy; 00533 } 00534 00535 void 00536 SlamGMapping::updateMap(const sensor_msgs::LaserScan& scan) 00537 { 00538 boost::mutex::scoped_lock(map_mutex_); 00539 GMapping::ScanMatcher matcher; 00540 double* laser_angles = new double[scan.ranges.size()]; 00541 double theta = scan.angle_min; 00542 for(unsigned int i=0; i<scan.ranges.size(); i++) 00543 { 00544 if (gsp_laser_angle_increment_ < 0) 00545 laser_angles[scan.ranges.size()-i-1]=theta; 00546 else 00547 laser_angles[i]=theta; 00548 theta += scan.angle_increment; 00549 } 00550 00551 matcher.setLaserParameters(scan.ranges.size(), laser_angles, 00552 gsp_laser_->getPose()); 00553 00554 delete[] laser_angles; 00555 matcher.setlaserMaxRange(maxRange_); 00556 matcher.setusableRange(maxUrange_); 00557 matcher.setgenerateMap(true); 00558 00559 GMapping::GridSlamProcessor::Particle best = 00560 gsp_->getParticles()[gsp_->getBestParticleIndex()]; 00561 std_msgs::Float64 entropy; 00562 entropy.data = computePoseEntropy(); 00563 if(entropy.data > 0.0) 00564 entropy_publisher_.publish(entropy); 00565 00566 if(!got_map_) { 00567 map_.map.info.resolution = delta_; 00568 map_.map.info.origin.position.x = 0.0; 00569 map_.map.info.origin.position.y = 0.0; 00570 map_.map.info.origin.position.z = 0.0; 00571 map_.map.info.origin.orientation.x = 0.0; 00572 map_.map.info.origin.orientation.y = 0.0; 00573 map_.map.info.origin.orientation.z = 0.0; 00574 map_.map.info.origin.orientation.w = 1.0; 00575 } 00576 00577 GMapping::Point center; 00578 center.x=(xmin_ + xmax_) / 2.0; 00579 center.y=(ymin_ + ymax_) / 2.0; 00580 00581 GMapping::ScanMatcherMap smap(center, xmin_, ymin_, xmax_, ymax_, 00582 delta_); 00583 00584 ROS_DEBUG("Trajectory tree:"); 00585 for(GMapping::GridSlamProcessor::TNode* n = best.node; 00586 n; 00587 n = n->parent) 00588 { 00589 ROS_DEBUG(" %.3f %.3f %.3f", 00590 n->pose.x, 00591 n->pose.y, 00592 n->pose.theta); 00593 if(!n->reading) 00594 { 00595 ROS_DEBUG("Reading is NULL"); 00596 continue; 00597 } 00598 matcher.invalidateActiveArea(); 00599 matcher.computeActiveArea(smap, n->pose, &((*n->reading)[0])); 00600 matcher.registerScan(smap, n->pose, &((*n->reading)[0])); 00601 } 00602 00603 // the map may have expanded, so resize ros message as well 00604 if(map_.map.info.width != (unsigned int) smap.getMapSizeX() || map_.map.info.height != (unsigned int) smap.getMapSizeY()) { 00605 00606 // NOTE: The results of ScanMatcherMap::getSize() are different from the parameters given to the constructor 00607 // so we must obtain the bounding box in a different way 00608 GMapping::Point wmin = smap.map2world(GMapping::IntPoint(0, 0)); 00609 GMapping::Point wmax = smap.map2world(GMapping::IntPoint(smap.getMapSizeX(), smap.getMapSizeY())); 00610 xmin_ = wmin.x; ymin_ = wmin.y; 00611 xmax_ = wmax.x; ymax_ = wmax.y; 00612 00613 ROS_DEBUG("map size is now %dx%d pixels (%f,%f)-(%f, %f)", smap.getMapSizeX(), smap.getMapSizeY(), 00614 xmin_, ymin_, xmax_, ymax_); 00615 00616 map_.map.info.width = smap.getMapSizeX(); 00617 map_.map.info.height = smap.getMapSizeY(); 00618 map_.map.info.origin.position.x = xmin_; 00619 map_.map.info.origin.position.y = ymin_; 00620 map_.map.data.resize(map_.map.info.width * map_.map.info.height); 00621 00622 ROS_DEBUG("map origin: (%f, %f)", map_.map.info.origin.position.x, map_.map.info.origin.position.y); 00623 } 00624 00625 for(int x=0; x < smap.getMapSizeX(); x++) 00626 { 00627 for(int y=0; y < smap.getMapSizeY(); y++) 00628 { 00630 GMapping::IntPoint p(x, y); 00631 double occ=smap.cell(p); 00632 assert(occ <= 1.0); 00633 if(occ < 0) 00634 map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = -1; 00635 else if(occ > occ_thresh_) 00636 { 00637 //map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = (int)round(occ*100.0); 00638 map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 100; 00639 } 00640 else 00641 map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 0; 00642 } 00643 } 00644 got_map_ = true; 00645 00646 //make sure to set the header information on the map 00647 map_.map.header.stamp = ros::Time::now(); 00648 map_.map.header.frame_id = map_frame_; 00649 00650 sst_.publish(map_.map); 00651 sstm_.publish(map_.map.info); 00652 } 00653 00654 bool 00655 SlamGMapping::mapCallback(nav_msgs::GetMap::Request &req, 00656 nav_msgs::GetMap::Response &res) 00657 { 00658 boost::mutex::scoped_lock(map_mutex_); 00659 if(got_map_ && map_.map.info.width && map_.map.info.height) 00660 { 00661 res = map_; 00662 return true; 00663 } 00664 else 00665 return false; 00666 } 00667 00668 void SlamGMapping::publishTransform() 00669 { 00670 map_to_odom_mutex_.lock(); 00671 ros::Time tf_expiration = ros::Time::now() + ros::Duration(0.05); 00672 tfB_->sendTransform( tf::StampedTransform (map_to_odom_, ros::Time::now(), map_frame_, odom_frame_)); 00673 map_to_odom_mutex_.unlock(); 00674 }