00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00108 #include "slam_gmapping.h"
00109
00110 #include <iostream>
00111
00112 #include <time.h>
00113
00114 #include "ros/ros.h"
00115 #include "ros/console.h"
00116 #include "nav_msgs/MapMetaData.h"
00117
00118 #include "gmapping/sensor/sensor_range/rangesensor.h"
00119 #include "gmapping/sensor/sensor_odometry/odometrysensor.h"
00120
00121 #include <rosbag/bag.h>
00122 #include <rosbag/view.h>
00123 #include <boost/foreach.hpp>
00124 #define foreach BOOST_FOREACH
00125
00126
00127 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
00128
00129 SlamGMapping::SlamGMapping():
00130 map_to_odom_(tf::Transform(tf::createQuaternionFromRPY( 0, 0, 0 ), tf::Point(0, 0, 0 ))),
00131 laser_count_(0), private_nh_("~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL)
00132 {
00133 seed_ = time(NULL);
00134 init();
00135 }
00136
00137 SlamGMapping::SlamGMapping(long unsigned int seed, long unsigned int max_duration_buffer):
00138 map_to_odom_(tf::Transform(tf::createQuaternionFromRPY( 0, 0, 0 ), tf::Point(0, 0, 0 ))),
00139 laser_count_(0), private_nh_("~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL),
00140 seed_(seed), tf_(ros::Duration(max_duration_buffer))
00141 {
00142 init();
00143 }
00144
00145
00146 void SlamGMapping::init()
00147 {
00148
00149
00150
00151
00152 gsp_ = new GMapping::GridSlamProcessor();
00153 ROS_ASSERT(gsp_);
00154
00155 tfB_ = new tf::TransformBroadcaster();
00156 ROS_ASSERT(tfB_);
00157
00158 gsp_laser_ = NULL;
00159 gsp_odom_ = NULL;
00160
00161 got_first_scan_ = false;
00162 got_map_ = false;
00163
00164
00165
00166
00167 if(!private_nh_.getParam("throttle_scans", throttle_scans_))
00168 throttle_scans_ = 1;
00169 if(!private_nh_.getParam("base_frame", base_frame_))
00170 base_frame_ = "base_link";
00171 if(!private_nh_.getParam("map_frame", map_frame_))
00172 map_frame_ = "map";
00173 if(!private_nh_.getParam("odom_frame", odom_frame_))
00174 odom_frame_ = "odom";
00175
00176 private_nh_.param("transform_publish_period", transform_publish_period_, 0.05);
00177
00178 double tmp;
00179 if(!private_nh_.getParam("map_update_interval", tmp))
00180 tmp = 5.0;
00181 map_update_interval_.fromSec(tmp);
00182
00183
00184 maxUrange_ = 0.0; maxRange_ = 0.0;
00185 if(!private_nh_.getParam("minimumScore", minimum_score_))
00186 minimum_score_ = 0;
00187 if(!private_nh_.getParam("sigma", sigma_))
00188 sigma_ = 0.05;
00189 if(!private_nh_.getParam("kernelSize", kernelSize_))
00190 kernelSize_ = 1;
00191 if(!private_nh_.getParam("lstep", lstep_))
00192 lstep_ = 0.05;
00193 if(!private_nh_.getParam("astep", astep_))
00194 astep_ = 0.05;
00195 if(!private_nh_.getParam("iterations", iterations_))
00196 iterations_ = 5;
00197 if(!private_nh_.getParam("lsigma", lsigma_))
00198 lsigma_ = 0.075;
00199 if(!private_nh_.getParam("ogain", ogain_))
00200 ogain_ = 3.0;
00201 if(!private_nh_.getParam("lskip", lskip_))
00202 lskip_ = 0;
00203 if(!private_nh_.getParam("srr", srr_))
00204 srr_ = 0.1;
00205 if(!private_nh_.getParam("srt", srt_))
00206 srt_ = 0.2;
00207 if(!private_nh_.getParam("str", str_))
00208 str_ = 0.1;
00209 if(!private_nh_.getParam("stt", stt_))
00210 stt_ = 0.2;
00211 if(!private_nh_.getParam("linearUpdate", linearUpdate_))
00212 linearUpdate_ = 1.0;
00213 if(!private_nh_.getParam("angularUpdate", angularUpdate_))
00214 angularUpdate_ = 0.5;
00215 if(!private_nh_.getParam("temporalUpdate", temporalUpdate_))
00216 temporalUpdate_ = -1.0;
00217 if(!private_nh_.getParam("resampleThreshold", resampleThreshold_))
00218 resampleThreshold_ = 0.5;
00219 if(!private_nh_.getParam("particles", particles_))
00220 particles_ = 30;
00221 if(!private_nh_.getParam("xmin", xmin_))
00222 xmin_ = -100.0;
00223 if(!private_nh_.getParam("ymin", ymin_))
00224 ymin_ = -100.0;
00225 if(!private_nh_.getParam("xmax", xmax_))
00226 xmax_ = 100.0;
00227 if(!private_nh_.getParam("ymax", ymax_))
00228 ymax_ = 100.0;
00229 if(!private_nh_.getParam("delta", delta_))
00230 delta_ = 0.05;
00231 if(!private_nh_.getParam("occ_thresh", occ_thresh_))
00232 occ_thresh_ = 0.25;
00233 if(!private_nh_.getParam("llsamplerange", llsamplerange_))
00234 llsamplerange_ = 0.01;
00235 if(!private_nh_.getParam("llsamplestep", llsamplestep_))
00236 llsamplestep_ = 0.01;
00237 if(!private_nh_.getParam("lasamplerange", lasamplerange_))
00238 lasamplerange_ = 0.005;
00239 if(!private_nh_.getParam("lasamplestep", lasamplestep_))
00240 lasamplestep_ = 0.005;
00241
00242 if(!private_nh_.getParam("tf_delay", tf_delay_))
00243 tf_delay_ = transform_publish_period_;
00244
00245 }
00246
00247
00248 void SlamGMapping::startLiveSlam()
00249 {
00250 entropy_publisher_ = private_nh_.advertise<std_msgs::Float64>("entropy", 1, true);
00251 sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00252 sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00253 ss_ = node_.advertiseService("dynamic_map", &SlamGMapping::mapCallback, this);
00254 scan_filter_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(node_, "scan", 5);
00255 scan_filter_ = new tf::MessageFilter<sensor_msgs::LaserScan>(*scan_filter_sub_, tf_, odom_frame_, 5);
00256 scan_filter_->registerCallback(boost::bind(&SlamGMapping::laserCallback, this, _1));
00257
00258 transform_thread_ = new boost::thread(boost::bind(&SlamGMapping::publishLoop, this, transform_publish_period_));
00259 }
00260
00261 void SlamGMapping::startReplay(const std::string & bag_fname, std::string scan_topic)
00262 {
00263 double transform_publish_period;
00264 ros::NodeHandle private_nh_("~");
00265 entropy_publisher_ = private_nh_.advertise<std_msgs::Float64>("entropy", 1, true);
00266 sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00267 sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00268 ss_ = node_.advertiseService("dynamic_map", &SlamGMapping::mapCallback, this);
00269
00270 rosbag::Bag bag;
00271 bag.open(bag_fname, rosbag::bagmode::Read);
00272
00273 std::vector<std::string> topics;
00274 topics.push_back(std::string("/tf"));
00275 topics.push_back(scan_topic);
00276 rosbag::View viewall(bag, rosbag::TopicQuery(topics));
00277
00278
00279 std::queue<std::pair<sensor_msgs::LaserScan::ConstPtr, std::string> > s_queue;
00280 foreach(rosbag::MessageInstance const m, viewall)
00281 {
00282 tf::tfMessage::ConstPtr cur_tf = m.instantiate<tf::tfMessage>();
00283 if (cur_tf != NULL) {
00284 for (size_t i = 0; i < cur_tf->transforms.size(); ++i)
00285 {
00286 geometry_msgs::TransformStamped transformStamped;
00287 tf::StampedTransform stampedTf;
00288 transformStamped = cur_tf->transforms[i];
00289 tf::transformStampedMsgToTF(transformStamped, stampedTf);
00290 tf_.setTransform(stampedTf);
00291 }
00292 }
00293
00294 sensor_msgs::LaserScan::ConstPtr s = m.instantiate<sensor_msgs::LaserScan>();
00295 if (s != NULL) {
00296 if (!(ros::Time(s->header.stamp)).is_zero())
00297 {
00298 s_queue.push(std::make_pair(s, ""));
00299 }
00300
00301 if (s_queue.size() > 5) {
00302 ROS_WARN_STREAM("Dropping old scan: " << s_queue.front().second);
00303 s_queue.pop();
00304 }
00305
00306 }
00307
00308
00309 while (!s_queue.empty())
00310 {
00311 try
00312 {
00313 tf::StampedTransform t;
00314 tf_.lookupTransform(s_queue.front().first->header.frame_id, odom_frame_, s_queue.front().first->header.stamp, t);
00315 this->laserCallback(s_queue.front().first);
00316 s_queue.pop();
00317 }
00318
00319 catch(tf2::TransformException& e)
00320 {
00321
00322 s_queue.front().second = std::string(e.what());
00323 break;
00324 }
00325 }
00326 }
00327
00328 bag.close();
00329 }
00330
00331 void SlamGMapping::publishLoop(double transform_publish_period){
00332 if(transform_publish_period == 0)
00333 return;
00334
00335 ros::Rate r(1.0 / transform_publish_period);
00336 while(ros::ok()){
00337 publishTransform();
00338 r.sleep();
00339 }
00340 }
00341
00342 SlamGMapping::~SlamGMapping()
00343 {
00344 if(transform_thread_){
00345 transform_thread_->join();
00346 delete transform_thread_;
00347 }
00348
00349 delete gsp_;
00350 if(gsp_laser_)
00351 delete gsp_laser_;
00352 if(gsp_odom_)
00353 delete gsp_odom_;
00354 if (scan_filter_)
00355 delete scan_filter_;
00356 if (scan_filter_sub_)
00357 delete scan_filter_sub_;
00358 }
00359
00360 bool
00361 SlamGMapping::getOdomPose(GMapping::OrientedPoint& gmap_pose, const ros::Time& t)
00362 {
00363
00364 centered_laser_pose_.stamp_ = t;
00365
00366 tf::Stamped<tf::Transform> odom_pose;
00367 try
00368 {
00369 tf_.transformPose(odom_frame_, centered_laser_pose_, odom_pose);
00370 }
00371 catch(tf::TransformException e)
00372 {
00373 ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
00374 return false;
00375 }
00376 double yaw = tf::getYaw(odom_pose.getRotation());
00377
00378 gmap_pose = GMapping::OrientedPoint(odom_pose.getOrigin().x(),
00379 odom_pose.getOrigin().y(),
00380 yaw);
00381 return true;
00382 }
00383
00384 bool
00385 SlamGMapping::initMapper(const sensor_msgs::LaserScan& scan)
00386 {
00387 laser_frame_ = scan.header.frame_id;
00388
00389 tf::Stamped<tf::Pose> ident;
00390 tf::Stamped<tf::Transform> laser_pose;
00391 ident.setIdentity();
00392 ident.frame_id_ = laser_frame_;
00393 ident.stamp_ = scan.header.stamp;
00394 try
00395 {
00396 tf_.transformPose(base_frame_, ident, laser_pose);
00397 }
00398 catch(tf::TransformException e)
00399 {
00400 ROS_WARN("Failed to compute laser pose, aborting initialization (%s)",
00401 e.what());
00402 return false;
00403 }
00404
00405
00406 tf::Vector3 v;
00407 v.setValue(0, 0, 1 + laser_pose.getOrigin().z());
00408 tf::Stamped<tf::Vector3> up(v, scan.header.stamp,
00409 base_frame_);
00410 try
00411 {
00412 tf_.transformPoint(laser_frame_, up, up);
00413 ROS_DEBUG("Z-Axis in sensor frame: %.3f", up.z());
00414 }
00415 catch(tf::TransformException& e)
00416 {
00417 ROS_WARN("Unable to determine orientation of laser: %s",
00418 e.what());
00419 return false;
00420 }
00421
00422
00423 if (fabs(fabs(up.z()) - 1) > 0.001)
00424 {
00425 ROS_WARN("Laser has to be mounted planar! Z-coordinate has to be 1 or -1, but gave: %.5f",
00426 up.z());
00427 return false;
00428 }
00429
00430 gsp_laser_beam_count_ = scan.ranges.size();
00431
00432 double angle_center = (scan.angle_min + scan.angle_max)/2;
00433
00434 if (up.z() > 0)
00435 {
00436 do_reverse_range_ = scan.angle_min > scan.angle_max;
00437 centered_laser_pose_ = tf::Stamped<tf::Pose>(tf::Transform(tf::createQuaternionFromRPY(0,0,angle_center),
00438 tf::Vector3(0,0,0)), ros::Time::now(), laser_frame_);
00439 ROS_INFO("Laser is mounted upwards.");
00440 }
00441 else
00442 {
00443 do_reverse_range_ = scan.angle_min < scan.angle_max;
00444 centered_laser_pose_ = tf::Stamped<tf::Pose>(tf::Transform(tf::createQuaternionFromRPY(M_PI,0,-angle_center),
00445 tf::Vector3(0,0,0)), ros::Time::now(), laser_frame_);
00446 ROS_INFO("Laser is mounted upside down.");
00447 }
00448
00449
00450 laser_angles_.resize(scan.ranges.size());
00451
00452 double theta = - std::fabs(scan.angle_min - scan.angle_max)/2;
00453 for(unsigned int i=0; i<scan.ranges.size(); ++i)
00454 {
00455 laser_angles_[i]=theta;
00456 theta += std::fabs(scan.angle_increment);
00457 }
00458
00459 ROS_DEBUG("Laser angles in laser-frame: min: %.3f max: %.3f inc: %.3f", scan.angle_min, scan.angle_max,
00460 scan.angle_increment);
00461 ROS_DEBUG("Laser angles in top-down centered laser-frame: min: %.3f max: %.3f inc: %.3f", laser_angles_.front(),
00462 laser_angles_.back(), std::fabs(scan.angle_increment));
00463
00464 GMapping::OrientedPoint gmap_pose(0, 0, 0);
00465
00466
00467 ros::NodeHandle private_nh_("~");
00468 if(!private_nh_.getParam("maxRange", maxRange_))
00469 maxRange_ = scan.range_max - 0.01;
00470 if(!private_nh_.getParam("maxUrange", maxUrange_))
00471 maxUrange_ = maxRange_;
00472
00473
00474
00475
00476
00477
00478 gsp_laser_ = new GMapping::RangeSensor("FLASER",
00479 gsp_laser_beam_count_,
00480 fabs(scan.angle_increment),
00481 gmap_pose,
00482 0.0,
00483 maxRange_);
00484 ROS_ASSERT(gsp_laser_);
00485
00486 GMapping::SensorMap smap;
00487 smap.insert(make_pair(gsp_laser_->getName(), gsp_laser_));
00488 gsp_->setSensorMap(smap);
00489
00490 gsp_odom_ = new GMapping::OdometrySensor(odom_frame_);
00491 ROS_ASSERT(gsp_odom_);
00492
00493
00495 GMapping::OrientedPoint initialPose;
00496 if(!getOdomPose(initialPose, scan.header.stamp))
00497 {
00498 ROS_WARN("Unable to determine inital pose of laser! Starting point will be set to zero.");
00499 initialPose = GMapping::OrientedPoint(0.0, 0.0, 0.0);
00500 }
00501
00502 gsp_->setMatchingParameters(maxUrange_, maxRange_, sigma_,
00503 kernelSize_, lstep_, astep_, iterations_,
00504 lsigma_, ogain_, lskip_);
00505
00506 gsp_->setMotionModelParameters(srr_, srt_, str_, stt_);
00507 gsp_->setUpdateDistances(linearUpdate_, angularUpdate_, resampleThreshold_);
00508 gsp_->setUpdatePeriod(temporalUpdate_);
00509 gsp_->setgenerateMap(false);
00510 gsp_->GridSlamProcessor::init(particles_, xmin_, ymin_, xmax_, ymax_,
00511 delta_, initialPose);
00512 gsp_->setllsamplerange(llsamplerange_);
00513 gsp_->setllsamplestep(llsamplestep_);
00517 gsp_->setlasamplerange(lasamplerange_);
00518 gsp_->setlasamplestep(lasamplestep_);
00519 gsp_->setminimumScore(minimum_score_);
00520
00521
00522 GMapping::sampleGaussian(1,seed_);
00523
00524 ROS_INFO("Initialization complete");
00525
00526 return true;
00527 }
00528
00529 bool
00530 SlamGMapping::addScan(const sensor_msgs::LaserScan& scan, GMapping::OrientedPoint& gmap_pose)
00531 {
00532 if(!getOdomPose(gmap_pose, scan.header.stamp))
00533 return false;
00534
00535 if(scan.ranges.size() != gsp_laser_beam_count_)
00536 return false;
00537
00538
00539 double* ranges_double = new double[scan.ranges.size()];
00540
00541 if (do_reverse_range_)
00542 {
00543 ROS_DEBUG("Inverting scan");
00544 int num_ranges = scan.ranges.size();
00545 for(int i=0; i < num_ranges; i++)
00546 {
00547
00548 if(scan.ranges[num_ranges - i - 1] < scan.range_min)
00549 ranges_double[i] = (double)scan.range_max;
00550 else
00551 ranges_double[i] = (double)scan.ranges[num_ranges - i - 1];
00552 }
00553 } else
00554 {
00555 for(unsigned int i=0; i < scan.ranges.size(); i++)
00556 {
00557
00558 if(scan.ranges[i] < scan.range_min)
00559 ranges_double[i] = (double)scan.range_max;
00560 else
00561 ranges_double[i] = (double)scan.ranges[i];
00562 }
00563 }
00564
00565 GMapping::RangeReading reading(scan.ranges.size(),
00566 ranges_double,
00567 gsp_laser_,
00568 scan.header.stamp.toSec());
00569
00570
00571
00572 delete[] ranges_double;
00573
00574 reading.setPose(gmap_pose);
00575
00576
00577
00578
00579
00580
00581
00582
00583 ROS_DEBUG("processing scan");
00584
00585 return gsp_->processScan(reading);
00586 }
00587
00588 void
00589 SlamGMapping::laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
00590 {
00591 laser_count_++;
00592 if ((laser_count_ % throttle_scans_) != 0)
00593 return;
00594
00595 static ros::Time last_map_update(0,0);
00596
00597
00598 if(!got_first_scan_)
00599 {
00600 if(!initMapper(*scan))
00601 return;
00602 got_first_scan_ = true;
00603 }
00604
00605 GMapping::OrientedPoint odom_pose;
00606
00607 if(addScan(*scan, odom_pose))
00608 {
00609 ROS_DEBUG("scan processed");
00610
00611 GMapping::OrientedPoint mpose = gsp_->getParticles()[gsp_->getBestParticleIndex()].pose;
00612 ROS_DEBUG("new best pose: %.3f %.3f %.3f", mpose.x, mpose.y, mpose.theta);
00613 ROS_DEBUG("odom pose: %.3f %.3f %.3f", odom_pose.x, odom_pose.y, odom_pose.theta);
00614 ROS_DEBUG("correction: %.3f %.3f %.3f", mpose.x - odom_pose.x, mpose.y - odom_pose.y, mpose.theta - odom_pose.theta);
00615
00616 tf::Transform laser_to_map = tf::Transform(tf::createQuaternionFromRPY(0, 0, mpose.theta), tf::Vector3(mpose.x, mpose.y, 0.0)).inverse();
00617 tf::Transform odom_to_laser = tf::Transform(tf::createQuaternionFromRPY(0, 0, odom_pose.theta), tf::Vector3(odom_pose.x, odom_pose.y, 0.0));
00618
00619 map_to_odom_mutex_.lock();
00620 map_to_odom_ = (odom_to_laser * laser_to_map).inverse();
00621 map_to_odom_mutex_.unlock();
00622
00623 if(!got_map_ || (scan->header.stamp - last_map_update) > map_update_interval_)
00624 {
00625 updateMap(*scan);
00626 last_map_update = scan->header.stamp;
00627 ROS_DEBUG("Updated the map");
00628 }
00629 } else
00630 ROS_DEBUG("cannot process scan");
00631 }
00632
00633 double
00634 SlamGMapping::computePoseEntropy()
00635 {
00636 double weight_total=0.0;
00637 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it = gsp_->getParticles().begin();
00638 it != gsp_->getParticles().end();
00639 ++it)
00640 {
00641 weight_total += it->weight;
00642 }
00643 double entropy = 0.0;
00644 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it = gsp_->getParticles().begin();
00645 it != gsp_->getParticles().end();
00646 ++it)
00647 {
00648 if(it->weight/weight_total > 0.0)
00649 entropy += it->weight/weight_total * log(it->weight/weight_total);
00650 }
00651 return -entropy;
00652 }
00653
00654 void
00655 SlamGMapping::updateMap(const sensor_msgs::LaserScan& scan)
00656 {
00657 ROS_DEBUG("Update map");
00658 boost::mutex::scoped_lock map_lock (map_mutex_);
00659 GMapping::ScanMatcher matcher;
00660
00661 matcher.setLaserParameters(scan.ranges.size(), &(laser_angles_[0]),
00662 gsp_laser_->getPose());
00663
00664 matcher.setlaserMaxRange(maxRange_);
00665 matcher.setusableRange(maxUrange_);
00666 matcher.setgenerateMap(true);
00667
00668 GMapping::GridSlamProcessor::Particle best =
00669 gsp_->getParticles()[gsp_->getBestParticleIndex()];
00670 std_msgs::Float64 entropy;
00671 entropy.data = computePoseEntropy();
00672 if(entropy.data > 0.0)
00673 entropy_publisher_.publish(entropy);
00674
00675 if(!got_map_) {
00676 map_.map.info.resolution = delta_;
00677 map_.map.info.origin.position.x = 0.0;
00678 map_.map.info.origin.position.y = 0.0;
00679 map_.map.info.origin.position.z = 0.0;
00680 map_.map.info.origin.orientation.x = 0.0;
00681 map_.map.info.origin.orientation.y = 0.0;
00682 map_.map.info.origin.orientation.z = 0.0;
00683 map_.map.info.origin.orientation.w = 1.0;
00684 }
00685
00686 GMapping::Point center;
00687 center.x=(xmin_ + xmax_) / 2.0;
00688 center.y=(ymin_ + ymax_) / 2.0;
00689
00690 GMapping::ScanMatcherMap smap(center, xmin_, ymin_, xmax_, ymax_,
00691 delta_);
00692
00693 ROS_DEBUG("Trajectory tree:");
00694 for(GMapping::GridSlamProcessor::TNode* n = best.node;
00695 n;
00696 n = n->parent)
00697 {
00698 ROS_DEBUG(" %.3f %.3f %.3f",
00699 n->pose.x,
00700 n->pose.y,
00701 n->pose.theta);
00702 if(!n->reading)
00703 {
00704 ROS_DEBUG("Reading is NULL");
00705 continue;
00706 }
00707 matcher.invalidateActiveArea();
00708 matcher.computeActiveArea(smap, n->pose, &((*n->reading)[0]));
00709 matcher.registerScan(smap, n->pose, &((*n->reading)[0]));
00710 }
00711
00712
00713 if(map_.map.info.width != (unsigned int) smap.getMapSizeX() || map_.map.info.height != (unsigned int) smap.getMapSizeY()) {
00714
00715
00716
00717 GMapping::Point wmin = smap.map2world(GMapping::IntPoint(0, 0));
00718 GMapping::Point wmax = smap.map2world(GMapping::IntPoint(smap.getMapSizeX(), smap.getMapSizeY()));
00719 xmin_ = wmin.x; ymin_ = wmin.y;
00720 xmax_ = wmax.x; ymax_ = wmax.y;
00721
00722 ROS_DEBUG("map size is now %dx%d pixels (%f,%f)-(%f, %f)", smap.getMapSizeX(), smap.getMapSizeY(),
00723 xmin_, ymin_, xmax_, ymax_);
00724
00725 map_.map.info.width = smap.getMapSizeX();
00726 map_.map.info.height = smap.getMapSizeY();
00727 map_.map.info.origin.position.x = xmin_;
00728 map_.map.info.origin.position.y = ymin_;
00729 map_.map.data.resize(map_.map.info.width * map_.map.info.height);
00730
00731 ROS_DEBUG("map origin: (%f, %f)", map_.map.info.origin.position.x, map_.map.info.origin.position.y);
00732 }
00733
00734 for(int x=0; x < smap.getMapSizeX(); x++)
00735 {
00736 for(int y=0; y < smap.getMapSizeY(); y++)
00737 {
00739 GMapping::IntPoint p(x, y);
00740 double occ=smap.cell(p);
00741 assert(occ <= 1.0);
00742 if(occ < 0)
00743 map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = -1;
00744 else if(occ > occ_thresh_)
00745 {
00746
00747 map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 100;
00748 }
00749 else
00750 map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 0;
00751 }
00752 }
00753 got_map_ = true;
00754
00755
00756 map_.map.header.stamp = ros::Time::now();
00757 map_.map.header.frame_id = tf_.resolve( map_frame_ );
00758
00759 sst_.publish(map_.map);
00760 sstm_.publish(map_.map.info);
00761 }
00762
00763 bool
00764 SlamGMapping::mapCallback(nav_msgs::GetMap::Request &req,
00765 nav_msgs::GetMap::Response &res)
00766 {
00767 boost::mutex::scoped_lock map_lock (map_mutex_);
00768 if(got_map_ && map_.map.info.width && map_.map.info.height)
00769 {
00770 res = map_;
00771 return true;
00772 }
00773 else
00774 return false;
00775 }
00776
00777 void SlamGMapping::publishTransform()
00778 {
00779 map_to_odom_mutex_.lock();
00780 ros::Time tf_expiration = ros::Time::now() + ros::Duration(tf_delay_);
00781 tfB_->sendTransform( tf::StampedTransform (map_to_odom_, tf_expiration, map_frame_, odom_frame_));
00782 map_to_odom_mutex_.unlock();
00783 }