slam_gmapping.cpp
Go to the documentation of this file.
1 /*
2  * slam_gmapping
3  * Copyright (c) 2008, Willow Garage, Inc.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright notice,
8  * this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
13  * contributors may be used to endorse or promote products derived from
14  * this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26  * POSSIBILITY OF SUCH DAMAGE.
27  *
28  */
29 
30 /* Author: Brian Gerkey */
31 /* Modified by: Charles DuHadway */
32 
33 
121 #include "slam_gmapping.h"
122 
123 #include <iostream>
124 
125 #include <time.h>
126 
127 #include "ros/ros.h"
128 #include "ros/console.h"
129 #include "nav_msgs/MapMetaData.h"
130 
133 
134 #include <rosbag/bag.h>
135 #include <rosbag/view.h>
136 #include <boost/foreach.hpp>
137 #define foreach BOOST_FOREACH
138 
139 // compute linear index for given map coords
140 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
141 
143  map_to_odom_(tf::Transform(tf::createQuaternionFromRPY( 0, 0, 0 ), tf::Point(0, 0, 0 ))),
144  laser_count_(0), private_nh_("~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL)
145 {
146  seed_ = time(NULL);
147  init();
148 }
149 
151  map_to_odom_(tf::Transform(tf::createQuaternionFromRPY( 0, 0, 0 ), tf::Point(0, 0, 0 ))),
152  laser_count_(0),node_(nh), private_nh_(pnh), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL)
153 {
154  seed_ = time(NULL);
155  init();
156 }
157 
158 SlamGMapping::SlamGMapping(long unsigned int seed, long unsigned int max_duration_buffer):
159  map_to_odom_(tf::Transform(tf::createQuaternionFromRPY( 0, 0, 0 ), tf::Point(0, 0, 0 ))),
160  laser_count_(0), private_nh_("~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL),
161  seed_(seed), tf_(ros::Duration(max_duration_buffer))
162 {
163  init();
164 }
165 
166 
168 {
169  // log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->setLevel(ros::console::g_level_lookup[ros::console::levels::Debug]);
170 
171  // The library is pretty chatty
172  //gsp_ = new GMapping::GridSlamProcessor(std::cerr);
174  ROS_ASSERT(gsp_);
175 
177  ROS_ASSERT(tfB_);
178 
179  gsp_laser_ = NULL;
180  gsp_odom_ = NULL;
181 
182  got_first_scan_ = false;
183  got_map_ = false;
184 
185 
186 
187  // Parameters used by our GMapping wrapper
188  if(!private_nh_.getParam("throttle_scans", throttle_scans_))
189  throttle_scans_ = 1;
190  if(!private_nh_.getParam("base_frame", base_frame_))
191  base_frame_ = "base_link";
192  if(!private_nh_.getParam("map_frame", map_frame_))
193  map_frame_ = "map";
194  if(!private_nh_.getParam("odom_frame", odom_frame_))
195  odom_frame_ = "odom";
196 
197  private_nh_.param("transform_publish_period", transform_publish_period_, 0.05);
198 
199  double tmp;
200  if(!private_nh_.getParam("map_update_interval", tmp))
201  tmp = 5.0;
203 
204  // Parameters used by GMapping itself
205  maxUrange_ = 0.0; maxRange_ = 0.0; // preliminary default, will be set in initMapper()
206  if(!private_nh_.getParam("minimumScore", minimum_score_))
207  minimum_score_ = 0;
208  if(!private_nh_.getParam("sigma", sigma_))
209  sigma_ = 0.05;
210  if(!private_nh_.getParam("kernelSize", kernelSize_))
211  kernelSize_ = 1;
212  if(!private_nh_.getParam("lstep", lstep_))
213  lstep_ = 0.05;
214  if(!private_nh_.getParam("astep", astep_))
215  astep_ = 0.05;
216  if(!private_nh_.getParam("iterations", iterations_))
217  iterations_ = 5;
218  if(!private_nh_.getParam("lsigma", lsigma_))
219  lsigma_ = 0.075;
220  if(!private_nh_.getParam("ogain", ogain_))
221  ogain_ = 3.0;
222  if(!private_nh_.getParam("lskip", lskip_))
223  lskip_ = 0;
224  if(!private_nh_.getParam("srr", srr_))
225  srr_ = 0.1;
226  if(!private_nh_.getParam("srt", srt_))
227  srt_ = 0.2;
228  if(!private_nh_.getParam("str", str_))
229  str_ = 0.1;
230  if(!private_nh_.getParam("stt", stt_))
231  stt_ = 0.2;
232  if(!private_nh_.getParam("linearUpdate", linearUpdate_))
233  linearUpdate_ = 1.0;
234  if(!private_nh_.getParam("angularUpdate", angularUpdate_))
235  angularUpdate_ = 0.5;
236  if(!private_nh_.getParam("temporalUpdate", temporalUpdate_))
237  temporalUpdate_ = -1.0;
238  if(!private_nh_.getParam("resampleThreshold", resampleThreshold_))
239  resampleThreshold_ = 0.5;
240  if(!private_nh_.getParam("particles", particles_))
241  particles_ = 30;
242  if(!private_nh_.getParam("xmin", xmin_))
243  xmin_ = -100.0;
244  if(!private_nh_.getParam("ymin", ymin_))
245  ymin_ = -100.0;
246  if(!private_nh_.getParam("xmax", xmax_))
247  xmax_ = 100.0;
248  if(!private_nh_.getParam("ymax", ymax_))
249  ymax_ = 100.0;
250  if(!private_nh_.getParam("delta", delta_))
251  delta_ = 0.05;
252  if(!private_nh_.getParam("occ_thresh", occ_thresh_))
253  occ_thresh_ = 0.25;
254  if(!private_nh_.getParam("llsamplerange", llsamplerange_))
255  llsamplerange_ = 0.01;
256  if(!private_nh_.getParam("llsamplestep", llsamplestep_))
257  llsamplestep_ = 0.01;
258  if(!private_nh_.getParam("lasamplerange", lasamplerange_))
259  lasamplerange_ = 0.005;
260  if(!private_nh_.getParam("lasamplestep", lasamplestep_))
261  lasamplestep_ = 0.005;
262 
263  if(!private_nh_.getParam("tf_delay", tf_delay_))
265 
266 }
267 
268 
270 {
271  entropy_publisher_ = private_nh_.advertise<std_msgs::Float64>("entropy", 1, true);
272  sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
273  sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
274  ss_ = node_.advertiseService("dynamic_map", &SlamGMapping::mapCallback, this);
277  scan_filter_->registerCallback([this](auto msg){ laserCallback(msg); });
278 
279  transform_thread_ = new boost::thread(boost::bind(&SlamGMapping::publishLoop, this, transform_publish_period_));
280 }
281 
282 void SlamGMapping::startReplay(const std::string & bag_fname, std::string scan_topic)
283 {
284  double transform_publish_period;
286  entropy_publisher_ = private_nh_.advertise<std_msgs::Float64>("entropy", 1, true);
287  sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
288  sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
289  ss_ = node_.advertiseService("dynamic_map", &SlamGMapping::mapCallback, this);
290 
291  rosbag::Bag bag;
292  bag.open(bag_fname, rosbag::bagmode::Read);
293 
294  std::vector<std::string> topics;
295  topics.push_back(std::string("/tf"));
296  topics.push_back(scan_topic);
297  rosbag::View viewall(bag, rosbag::TopicQuery(topics));
298 
299  // Store up to 5 messages and there error message (if they cannot be processed right away)
300  std::queue<std::pair<sensor_msgs::LaserScan::ConstPtr, std::string> > s_queue;
301  foreach(rosbag::MessageInstance const m, viewall)
302  {
303  tf::tfMessage::ConstPtr cur_tf = m.instantiate<tf::tfMessage>();
304  if (cur_tf != NULL) {
305  for (size_t i = 0; i < cur_tf->transforms.size(); ++i)
306  {
307  geometry_msgs::TransformStamped transformStamped;
308  tf::StampedTransform stampedTf;
309  transformStamped = cur_tf->transforms[i];
310  tf::transformStampedMsgToTF(transformStamped, stampedTf);
311  tf_.setTransform(stampedTf);
312  }
313  }
314 
315  sensor_msgs::LaserScan::ConstPtr s = m.instantiate<sensor_msgs::LaserScan>();
316  if (s != NULL) {
317  if (!(ros::Time(s->header.stamp)).is_zero())
318  {
319  s_queue.push(std::make_pair(s, ""));
320  }
321  // Just like in live processing, only process the latest 5 scans
322  if (s_queue.size() > 5) {
323  ROS_WARN_STREAM("Dropping old scan: " << s_queue.front().second);
324  s_queue.pop();
325  }
326  // ignoring un-timestamped tf data
327  }
328 
329  // Only process a scan if it has tf data
330  while (!s_queue.empty())
331  {
332  try
333  {
335  tf_.lookupTransform(s_queue.front().first->header.frame_id, odom_frame_, s_queue.front().first->header.stamp, t);
336  this->laserCallback(s_queue.front().first);
337  s_queue.pop();
338  }
339  // If tf does not have the data yet
340  catch(tf2::TransformException& e)
341  {
342  // Store the error to display it if we cannot process the data after some time
343  s_queue.front().second = std::string(e.what());
344  break;
345  }
346  }
347  }
348 
349  bag.close();
350 }
351 
352 void SlamGMapping::publishLoop(double transform_publish_period){
353  if(transform_publish_period == 0)
354  return;
355 
356  ros::Rate r(1.0 / transform_publish_period);
357  while(ros::ok()){
359  r.sleep();
360  }
361 }
362 
364 {
365  if(transform_thread_){
366  transform_thread_->join();
367  delete transform_thread_;
368  }
369 
370  delete gsp_;
371  if(gsp_laser_)
372  delete gsp_laser_;
373  if(gsp_odom_)
374  delete gsp_odom_;
375  if (scan_filter_)
376  delete scan_filter_;
377  if (scan_filter_sub_)
378  delete scan_filter_sub_;
379 }
380 
381 bool
383 {
384  // Get the pose of the centered laser at the right time
385  centered_laser_pose_.stamp_ = t;
386  // Get the laser's pose that is centered
387  tf::Stamped<tf::Transform> odom_pose;
388  try
389  {
391  }
392  catch(tf::TransformException e)
393  {
394  ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
395  return false;
396  }
397  double yaw = tf::getYaw(odom_pose.getRotation());
398 
399  gmap_pose = GMapping::OrientedPoint(odom_pose.getOrigin().x(),
400  odom_pose.getOrigin().y(),
401  yaw);
402  return true;
403 }
404 
405 bool
406 SlamGMapping::initMapper(const sensor_msgs::LaserScan& scan)
407 {
408  laser_frame_ = scan.header.frame_id;
409  // Get the laser's pose, relative to base.
410  tf::Stamped<tf::Pose> ident;
411  tf::Stamped<tf::Transform> laser_pose;
412  ident.setIdentity();
413  ident.frame_id_ = laser_frame_;
414  ident.stamp_ = scan.header.stamp;
415  try
416  {
417  tf_.transformPose(base_frame_, ident, laser_pose);
418  }
419  catch(tf::TransformException e)
420  {
421  ROS_WARN("Failed to compute laser pose, aborting initialization (%s)",
422  e.what());
423  return false;
424  }
425 
426  // create a point 1m above the laser position and transform it into the laser-frame
427  tf::Vector3 v;
428  v.setValue(0, 0, 1 + laser_pose.getOrigin().z());
429  tf::Stamped<tf::Vector3> up(v, scan.header.stamp,
430  base_frame_);
431  try
432  {
434  ROS_DEBUG("Z-Axis in sensor frame: %.3f", up.z());
435  }
436  catch(tf::TransformException& e)
437  {
438  ROS_WARN("Unable to determine orientation of laser: %s",
439  e.what());
440  return false;
441  }
442 
443  // gmapping doesnt take roll or pitch into account. So check for correct sensor alignment.
444  if (fabs(fabs(up.z()) - 1) > 0.001)
445  {
446  ROS_WARN("Laser has to be mounted planar! Z-coordinate has to be 1 or -1, but gave: %.5f",
447  up.z());
448  return false;
449  }
450 
451  gsp_laser_beam_count_ = scan.ranges.size();
452 
453  double angle_center = (scan.angle_min + scan.angle_max)/2;
454 
455  if (up.z() > 0)
456  {
457  do_reverse_range_ = scan.angle_min > scan.angle_max;
459  tf::Vector3(0,0,0)), ros::Time::now(), laser_frame_);
460  ROS_INFO("Laser is mounted upwards.");
461  }
462  else
463  {
464  do_reverse_range_ = scan.angle_min < scan.angle_max;
466  tf::Vector3(0,0,0)), ros::Time::now(), laser_frame_);
467  ROS_INFO("Laser is mounted upside down.");
468  }
469 
470  // Compute the angles of the laser from -x to x, basically symmetric and in increasing order
471  laser_angles_.resize(scan.ranges.size());
472  // Make sure angles are started so that they are centered
473  double theta = - std::fabs(scan.angle_min - scan.angle_max)/2;
474  for(unsigned int i=0; i<scan.ranges.size(); ++i)
475  {
476  laser_angles_[i]=theta;
477  theta += std::fabs(scan.angle_increment);
478  }
479 
480  ROS_DEBUG("Laser angles in laser-frame: min: %.3f max: %.3f inc: %.3f", scan.angle_min, scan.angle_max,
481  scan.angle_increment);
482  ROS_DEBUG("Laser angles in top-down centered laser-frame: min: %.3f max: %.3f inc: %.3f", laser_angles_.front(),
483  laser_angles_.back(), std::fabs(scan.angle_increment));
484 
485  GMapping::OrientedPoint gmap_pose(0, 0, 0);
486 
487  // setting maxRange and maxUrange here so we can set a reasonable default
489  if(!private_nh_.getParam("maxRange", maxRange_))
490  maxRange_ = scan.range_max - 0.01;
491  if(!private_nh_.getParam("maxUrange", maxUrange_))
493 
494  // The laser must be called "FLASER".
495  // We pass in the absolute value of the computed angle increment, on the
496  // assumption that GMapping requires a positive angle increment. If the
497  // actual increment is negative, we'll swap the order of ranges before
498  // feeding each scan to GMapping.
499  gsp_laser_ = new GMapping::RangeSensor("FLASER",
501  fabs(scan.angle_increment),
502  gmap_pose,
503  0.0,
504  maxRange_);
506 
507  GMapping::SensorMap smap;
508  smap.insert(make_pair(gsp_laser_->getName(), gsp_laser_));
509  gsp_->setSensorMap(smap);
510 
513 
514 
516  GMapping::OrientedPoint initialPose;
517  if(!getOdomPose(initialPose, scan.header.stamp))
518  {
519  ROS_WARN("Unable to determine inital pose of laser! Starting point will be set to zero.");
520  initialPose = GMapping::OrientedPoint(0.0, 0.0, 0.0);
521  }
522 
525  lsigma_, ogain_, lskip_);
526 
530  gsp_->setgenerateMap(false);
531  gsp_->GridSlamProcessor::init(particles_, xmin_, ymin_, xmax_, ymax_,
532  delta_, initialPose);
533  gsp_->setllsamplerange(llsamplerange_);
534  gsp_->setllsamplestep(llsamplestep_);
538  gsp_->setlasamplerange(lasamplerange_);
539  gsp_->setlasamplestep(lasamplestep_);
540  gsp_->setminimumScore(minimum_score_);
541 
542  // Call the sampling function once to set the seed.
544 
545  ROS_INFO("Initialization complete");
546 
547  return true;
548 }
549 
550 bool
551 SlamGMapping::addScan(const sensor_msgs::LaserScan& scan, GMapping::OrientedPoint& gmap_pose)
552 {
553  if(!getOdomPose(gmap_pose, scan.header.stamp))
554  return false;
555 
556  if(scan.ranges.size() != gsp_laser_beam_count_)
557  return false;
558 
559  // GMapping wants an array of doubles...
560  double* ranges_double = new double[scan.ranges.size()];
561  // If the angle increment is negative, we have to invert the order of the readings.
562  if (do_reverse_range_)
563  {
564  ROS_DEBUG("Inverting scan");
565  int num_ranges = scan.ranges.size();
566  for(int i=0; i < num_ranges; i++)
567  {
568  // Must filter out short readings, because the mapper won't
569  if(scan.ranges[num_ranges - i - 1] < scan.range_min)
570  ranges_double[i] = (double)scan.range_max;
571  else
572  ranges_double[i] = (double)scan.ranges[num_ranges - i - 1];
573  }
574  } else
575  {
576  for(unsigned int i=0; i < scan.ranges.size(); i++)
577  {
578  // Must filter out short readings, because the mapper won't
579  if(scan.ranges[i] < scan.range_min)
580  ranges_double[i] = (double)scan.range_max;
581  else
582  ranges_double[i] = (double)scan.ranges[i];
583  }
584  }
585 
586  GMapping::RangeReading reading(scan.ranges.size(),
587  ranges_double,
588  gsp_laser_,
589  scan.header.stamp.toSec());
590 
591  // ...but it deep copies them in RangeReading constructor, so we don't
592  // need to keep our array around.
593  delete[] ranges_double;
594 
595  reading.setPose(gmap_pose);
596 
597  /*
598  ROS_DEBUG("scanpose (%.3f): %.3f %.3f %.3f\n",
599  scan.header.stamp.toSec(),
600  gmap_pose.x,
601  gmap_pose.y,
602  gmap_pose.theta);
603  */
604  ROS_DEBUG("processing scan");
605 
606  return gsp_->processScan(reading);
607 }
608 
609 void
610 SlamGMapping::laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
611 {
612  laser_count_++;
613  if ((laser_count_ % throttle_scans_) != 0)
614  return;
615 
616  static ros::Time last_map_update(0,0);
617 
618  // We can't initialize the mapper until we've got the first scan
619  if(!got_first_scan_)
620  {
621  if(!initMapper(*scan))
622  return;
623  got_first_scan_ = true;
624  }
625 
626  GMapping::OrientedPoint odom_pose;
627 
628  if(addScan(*scan, odom_pose))
629  {
630  ROS_DEBUG("scan processed");
631 
633  ROS_DEBUG("new best pose: %.3f %.3f %.3f", mpose.x, mpose.y, mpose.theta);
634  ROS_DEBUG("odom pose: %.3f %.3f %.3f", odom_pose.x, odom_pose.y, odom_pose.theta);
635  ROS_DEBUG("correction: %.3f %.3f %.3f", mpose.x - odom_pose.x, mpose.y - odom_pose.y, mpose.theta - odom_pose.theta);
636 
637  tf::Transform laser_to_map = tf::Transform(tf::createQuaternionFromRPY(0, 0, mpose.theta), tf::Vector3(mpose.x, mpose.y, 0.0)).inverse();
638  tf::Transform odom_to_laser = tf::Transform(tf::createQuaternionFromRPY(0, 0, odom_pose.theta), tf::Vector3(odom_pose.x, odom_pose.y, 0.0));
639 
640  map_to_odom_mutex_.lock();
641  map_to_odom_ = (odom_to_laser * laser_to_map).inverse();
642  map_to_odom_mutex_.unlock();
643 
644  if(!got_map_ || (scan->header.stamp - last_map_update) > map_update_interval_)
645  {
646  updateMap(*scan);
647  last_map_update = scan->header.stamp;
648  ROS_DEBUG("Updated the map");
649  }
650  } else
651  ROS_DEBUG("cannot process scan");
652 }
653 
654 double
656 {
657  double weight_total=0.0;
658  for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it = gsp_->getParticles().begin();
659  it != gsp_->getParticles().end();
660  ++it)
661  {
662  weight_total += it->weight;
663  }
664  double entropy = 0.0;
665  for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it = gsp_->getParticles().begin();
666  it != gsp_->getParticles().end();
667  ++it)
668  {
669  if(it->weight/weight_total > 0.0)
670  entropy += it->weight/weight_total * log(it->weight/weight_total);
671  }
672  return -entropy;
673 }
674 
675 void
676 SlamGMapping::updateMap(const sensor_msgs::LaserScan& scan)
677 {
678  ROS_DEBUG("Update map");
679  boost::mutex::scoped_lock map_lock (map_mutex_);
680  GMapping::ScanMatcher matcher;
681 
682  matcher.setLaserParameters(scan.ranges.size(), &(laser_angles_[0]),
683  gsp_laser_->getPose());
684 
685  matcher.setlaserMaxRange(maxRange_);
686  matcher.setusableRange(maxUrange_);
687  matcher.setgenerateMap(true);
688 
691  std_msgs::Float64 entropy;
692  entropy.data = computePoseEntropy();
693  if(entropy.data > 0.0)
694  entropy_publisher_.publish(entropy);
695 
696  if(!got_map_) {
697  map_.map.info.resolution = delta_;
698  map_.map.info.origin.position.x = 0.0;
699  map_.map.info.origin.position.y = 0.0;
700  map_.map.info.origin.position.z = 0.0;
701  map_.map.info.origin.orientation.x = 0.0;
702  map_.map.info.origin.orientation.y = 0.0;
703  map_.map.info.origin.orientation.z = 0.0;
704  map_.map.info.origin.orientation.w = 1.0;
705  }
706 
707  GMapping::Point center;
708  center.x=(xmin_ + xmax_) / 2.0;
709  center.y=(ymin_ + ymax_) / 2.0;
710 
712  delta_);
713 
714  ROS_DEBUG("Trajectory tree:");
716  n;
717  n = n->parent)
718  {
719  ROS_DEBUG(" %.3f %.3f %.3f",
720  n->pose.x,
721  n->pose.y,
722  n->pose.theta);
723  if(!n->reading)
724  {
725  ROS_DEBUG("Reading is NULL");
726  continue;
727  }
728  matcher.invalidateActiveArea();
729  matcher.computeActiveArea(smap, n->pose, &((*n->reading)[0]));
730  matcher.registerScan(smap, n->pose, &((*n->reading)[0]));
731  }
732 
733  // the map may have expanded, so resize ros message as well
734  if(map_.map.info.width != (unsigned int) smap.getMapSizeX() || map_.map.info.height != (unsigned int) smap.getMapSizeY()) {
735 
736  // NOTE: The results of ScanMatcherMap::getSize() are different from the parameters given to the constructor
737  // so we must obtain the bounding box in a different way
738  GMapping::Point wmin = smap.map2world(GMapping::IntPoint(0, 0));
740  xmin_ = wmin.x; ymin_ = wmin.y;
741  xmax_ = wmax.x; ymax_ = wmax.y;
742 
743  ROS_DEBUG("map size is now %dx%d pixels (%f,%f)-(%f, %f)", smap.getMapSizeX(), smap.getMapSizeY(),
744  xmin_, ymin_, xmax_, ymax_);
745 
746  map_.map.info.width = smap.getMapSizeX();
747  map_.map.info.height = smap.getMapSizeY();
748  map_.map.info.origin.position.x = xmin_;
749  map_.map.info.origin.position.y = ymin_;
750  map_.map.data.resize(map_.map.info.width * map_.map.info.height);
751 
752  ROS_DEBUG("map origin: (%f, %f)", map_.map.info.origin.position.x, map_.map.info.origin.position.y);
753  }
754 
755  for(int x=0; x < smap.getMapSizeX(); x++)
756  {
757  for(int y=0; y < smap.getMapSizeY(); y++)
758  {
760  GMapping::IntPoint p(x, y);
761  double occ=smap.cell(p);
762  assert(occ <= 1.0);
763  if(occ < 0)
764  map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = -1;
765  else if(occ > occ_thresh_)
766  {
767  //map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = (int)round(occ*100.0);
768  map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 100;
769  }
770  else
771  map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 0;
772  }
773  }
774  got_map_ = true;
775 
776  //make sure to set the header information on the map
777  map_.map.header.stamp = ros::Time::now();
778  map_.map.header.frame_id = tf_.resolve( map_frame_ );
779 
780  sst_.publish(map_.map);
781  sstm_.publish(map_.map.info);
782 }
783 
784 bool
785 SlamGMapping::mapCallback(nav_msgs::GetMap::Request &req,
786  nav_msgs::GetMap::Response &res)
787 {
788  boost::mutex::scoped_lock map_lock (map_mutex_);
789  if(got_map_ && map_.map.info.width && map_.map.info.height)
790  {
791  res = map_;
792  return true;
793  }
794  else
795  return false;
796 }
797 
799 {
800  map_to_odom_mutex_.lock();
801  ros::Time tf_expiration = ros::Time::now() + ros::Duration(tf_delay_);
803  map_to_odom_mutex_.unlock();
804 }
GMapping::RangeReading::setPose
void setPose(const OrientedPoint &pose)
tf::Transform::getRotation
Quaternion getRotation() const
GMapping::SensorMap
std::map< std::string, Sensor * > SensorMap
rosbag::Bag
GMapping::Map::getMapSizeY
int getMapSizeY() const
SlamGMapping::seed_
unsigned long int seed_
Definition: slam_gmapping.h:149
MAP_IDX
#define MAP_IDX(sx, i, j)
Definition: slam_gmapping.cpp:140
SlamGMapping::str_
double str_
Definition: slam_gmapping.h:129
DurationBase< Duration >::fromSec
Duration & fromSec(double t)
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
SlamGMapping::getOdomPose
bool getOdomPose(GMapping::OrientedPoint &gmap_pose, const ros::Time &t)
Definition: slam_gmapping.cpp:382
SlamGMapping::SlamGMapping
SlamGMapping()
Definition: slam_gmapping.cpp:142
GMapping::GridSlamProcessor::getBestParticleIndex
int getBestParticleIndex() const
SlamGMapping::throttle_scans_
int throttle_scans_
Definition: slam_gmapping.h:99
SlamGMapping::tf_
tf::TransformListener tf_
Definition: slam_gmapping.h:70
SlamGMapping::gsp_laser_
GMapping::RangeSensor * gsp_laser_
Definition: slam_gmapping.h:76
SlamGMapping::scan_filter_
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
Definition: slam_gmapping.h:72
GMapping::GridSlamProcessor::setMatchingParameters
void setMatchingParameters(double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations, double likelihoodSigma=1, double likelihoodGain=1, unsigned int likelihoodSkip=0)
SlamGMapping::computePoseEntropy
double computePoseEntropy()
Definition: slam_gmapping.cpp:655
rosbag::MessageInstance
SlamGMapping::updateMap
void updateMap(const sensor_msgs::LaserScan &scan)
Definition: slam_gmapping.cpp:676
GMapping::RangeSensor::getPose
OrientedPoint getPose() const
tf::TransformListener::resolve
std::string resolve(const std::string &frame_name)
s
XmlRpcServer s
ros
tf::TransformListener::transformPose
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
SlamGMapping::publishTransform
void publishTransform()
Definition: slam_gmapping.cpp:798
time.h
slam_gmapping.h
GMapping::Map::cell
Cell & cell(const IntPoint &p)
SlamGMapping::gsp_laser_beam_count_
unsigned int gsp_laser_beam_count_
Definition: slam_gmapping.h:85
tf::Transformer::setTransform
bool setTransform(const StampedTransform &transform, const std::string &authority="default_authority")
n
#define n
tf::TransformListener::transformPoint
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
GMapping::Sensor::getName
std::string getName() const
SlamGMapping::do_reverse_range_
bool do_reverse_range_
Definition: slam_gmapping.h:84
SlamGMapping::laser_count_
int laser_count_
Definition: slam_gmapping.h:98
GMapping::Map::map2world
Point map2world(const IntPoint &p) const
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
SlamGMapping::delta_
double delta_
Definition: slam_gmapping.h:140
SlamGMapping::initMapper
bool initMapper(const sensor_msgs::LaserScan &scan)
Definition: slam_gmapping.cpp:406
GMapping::sampleGaussian
double UTILS_EXPORT sampleGaussian(double sigma, unsigned long int S=0)
GMapping::GridSlamProcessor::processScan
bool processScan(const RangeReading &reading, int adaptParticles=0)
SlamGMapping::srr_
double srr_
Definition: slam_gmapping.h:127
rosbag::Bag::close
void close()
tf::StampedTransform
SlamGMapping::gsp_odom_
GMapping::OdometrySensor * gsp_odom_
Definition: slam_gmapping.h:86
bag.h
SlamGMapping::got_map_
bool got_map_
Definition: slam_gmapping.h:90
SlamGMapping::centered_laser_pose_
tf::Stamped< tf::Pose > centered_laser_pose_
Definition: slam_gmapping.h:81
GMapping::ScanMatcher::invalidateActiveArea
void invalidateActiveArea()
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
GMapping::ScanMatcher
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
SlamGMapping::node_
ros::NodeHandle node_
Definition: slam_gmapping.h:65
ros::ok
ROSCPP_DECL bool ok()
rosbag::bagmode::Read
Read
SlamGMapping::ss_
ros::ServiceServer ss_
Definition: slam_gmapping.h:69
SlamGMapping::sigma_
double sigma_
Definition: slam_gmapping.h:119
SlamGMapping::got_first_scan_
bool got_first_scan_
Definition: slam_gmapping.h:88
SlamGMapping::tfB_
tf::TransformBroadcaster * tfB_
Definition: slam_gmapping.h:73
message_filters::Subscriber< sensor_msgs::LaserScan >
GMapping::Map< PointAccumulator, HierarchicalArray2D< PointAccumulator > >
GMapping::OrientedPoint
orientedpoint< double, double > OrientedPoint
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
tf::Stamped< tf::Transform >
GMapping::ScanMatcher::setLaserParameters
void setLaserParameters(unsigned int beams, double *angles, const OrientedPoint &lpose)
console.h
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
SlamGMapping::map_update_interval_
ros::Duration map_update_interval_
Definition: slam_gmapping.h:93
SlamGMapping::temporalUpdate_
double temporalUpdate_
Definition: slam_gmapping.h:133
SlamGMapping::llsamplestep_
double llsamplestep_
Definition: slam_gmapping.h:143
SlamGMapping::entropy_publisher_
ros::Publisher entropy_publisher_
Definition: slam_gmapping.h:66
tf::Transform::inverse
Transform inverse() const
GMapping::Map::getMapSizeX
int getMapSizeX() const
SlamGMapping::lskip_
int lskip_
Definition: slam_gmapping.h:126
SlamGMapping::minimum_score_
double minimum_score_
Definition: slam_gmapping.h:118
SlamGMapping::ogain_
double ogain_
Definition: slam_gmapping.h:125
ROS_DEBUG
#define ROS_DEBUG(...)
GMapping::GridSlamProcessor
tf::TransformBroadcaster
SlamGMapping::map_mutex_
boost::mutex map_mutex_
Definition: slam_gmapping.h:96
SlamGMapping::startReplay
void startReplay(const std::string &bag_fname, std::string scan_topic)
Definition: slam_gmapping.cpp:282
GMapping::GridSlamProcessor::Particle
GMapping::GridSlamProcessor::Particle::node
TNode * node
GMapping::point::y
T y
GMapping::GridSlamProcessor::setUpdateDistances
void setUpdateDistances(double linear, double angular, double resampleThreshold)
SlamGMapping::map_to_odom_
tf::Transform map_to_odom_
Definition: slam_gmapping.h:94
orientedpoint< double, double >::theta
double theta
GMapping::GridSlamProcessor::TNode
rangesensor.h
SlamGMapping::stt_
double stt_
Definition: slam_gmapping.h:130
ROS_WARN
#define ROS_WARN(...)
SlamGMapping::xmin_
double xmin_
Definition: slam_gmapping.h:136
SlamGMapping::maxRange_
double maxRange_
Definition: slam_gmapping.h:115
GMapping::GridSlamProcessor::getParticles
const ParticleVector & getParticles() const
SlamGMapping::angularUpdate_
double angularUpdate_
Definition: slam_gmapping.h:132
tf::transformStampedMsgToTF
static void transformStampedMsgToTF(const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
SlamGMapping::addScan
bool addScan(const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose)
Definition: slam_gmapping.cpp:551
tf::Transform
SlamGMapping::scan_filter_sub_
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
Definition: slam_gmapping.h:71
SlamGMapping::ymax_
double ymax_
Definition: slam_gmapping.h:139
SlamGMapping::base_frame_
std::string base_frame_
Definition: slam_gmapping.h:103
SlamGMapping::srt_
double srt_
Definition: slam_gmapping.h:128
SlamGMapping::lstep_
double lstep_
Definition: slam_gmapping.h:121
ros::Rate::sleep
bool sleep()
point< double >
SlamGMapping::startLiveSlam
void startLiveSlam()
Definition: slam_gmapping.cpp:269
rosbag::TopicQuery
SlamGMapping::resampleThreshold_
double resampleThreshold_
Definition: slam_gmapping.h:134
SlamGMapping::occ_thresh_
double occ_thresh_
Definition: slam_gmapping.h:141
GMapping::GridSlamProcessor::setSensorMap
void setSensorMap(const SensorMap &smap)
SlamGMapping::llsamplerange_
double llsamplerange_
Definition: slam_gmapping.h:142
SlamGMapping::lasamplestep_
double lasamplestep_
Definition: slam_gmapping.h:145
GMapping::RangeReading
view.h
rosbag::View
SlamGMapping::sstm_
ros::Publisher sstm_
Definition: slam_gmapping.h:68
SlamGMapping::map_to_odom_mutex_
boost::mutex map_to_odom_mutex_
Definition: slam_gmapping.h:95
ros::Time
SlamGMapping::publishLoop
void publishLoop(double transform_publish_period)
Definition: slam_gmapping.cpp:352
SlamGMapping::tf_delay_
double tf_delay_
Definition: slam_gmapping.h:152
SlamGMapping::private_nh_
ros::NodeHandle private_nh_
Definition: slam_gmapping.h:147
GMapping::GridSlamProcessor::setMotionModelParameters
void setMotionModelParameters(double srr, double srt, double str, double stt)
tf::MessageFilter< sensor_msgs::LaserScan >
odometrysensor.h
SlamGMapping::linearUpdate_
double linearUpdate_
Definition: slam_gmapping.h:131
GMapping::GridSlamProcessor::setUpdatePeriod
void setUpdatePeriod(double p)
SlamGMapping::transform_thread_
boost::thread * transform_thread_
Definition: slam_gmapping.h:101
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
SlamGMapping::lsigma_
double lsigma_
Definition: slam_gmapping.h:124
tf::createQuaternionFromRPY
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
SlamGMapping::iterations_
int iterations_
Definition: slam_gmapping.h:123
SlamGMapping::~SlamGMapping
~SlamGMapping()
Definition: slam_gmapping.cpp:363
rosbag::MessageInstance::instantiate
boost::shared_ptr< T > instantiate() const
SlamGMapping::laser_frame_
std::string laser_frame_
Definition: slam_gmapping.h:104
tf::Stamped::frame_id_
std::string frame_id_
ros::Rate
SlamGMapping::sst_
ros::Publisher sst_
Definition: slam_gmapping.h:67
tf
GMapping::ScanMatcher::computeActiveArea
void computeActiveArea(ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
SlamGMapping::maxUrange_
double maxUrange_
Definition: slam_gmapping.h:116
inverse
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
SlamGMapping::transform_publish_period_
double transform_publish_period_
Definition: slam_gmapping.h:151
GMapping::RangeSensor
SlamGMapping::xmax_
double xmax_
Definition: slam_gmapping.h:138
orientedpoint< double, double >
tf::Stamped::stamp_
ros::Time stamp_
SlamGMapping::odom_frame_
std::string odom_frame_
Definition: slam_gmapping.h:106
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
rosbag::Bag::open
void open(std::string const &filename, uint32_t mode=bagmode::Read)
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
SlamGMapping::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: slam_gmapping.cpp:785
GMapping::ScanMatcher::registerScan
double registerScan(ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
SlamGMapping::init
void init()
Definition: slam_gmapping.cpp:167
ros::Duration
SlamGMapping::kernelSize_
int kernelSize_
Definition: slam_gmapping.h:120
SlamGMapping::map_
nav_msgs::GetMap::Response map_
Definition: slam_gmapping.h:91
SlamGMapping::map_frame_
std::string map_frame_
Definition: slam_gmapping.h:105
GMapping::OdometrySensor
SlamGMapping::astep_
double astep_
Definition: slam_gmapping.h:122
SlamGMapping::lasamplerange_
double lasamplerange_
Definition: slam_gmapping.h:144
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
SlamGMapping::laser_angles_
std::vector< double > laser_angles_
Definition: slam_gmapping.h:79
GMapping::point::x
T x
ros::NodeHandle
SlamGMapping::laserCallback
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: slam_gmapping.cpp:610
SlamGMapping::particles_
int particles_
Definition: slam_gmapping.h:135
SlamGMapping::gsp_
GMapping::GridSlamProcessor * gsp_
Definition: slam_gmapping.h:75
ros::Time::now
static Time now()
SlamGMapping::ymin_
double ymin_
Definition: slam_gmapping.h:137


gmapping
Author(s): Brian Gerkey
autogenerated on Wed Aug 21 2024 02:12:11