slam_karto.cpp
Go to the documentation of this file.
1 /*
2  * slam_karto
3  * Copyright (c) 2008, Willow Garage, Inc.
4  *
5  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9  *
10  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13  * CONDITIONS.
14  *
15  */
16 
17 /* Author: Brian Gerkey */
18 
27 #include "ros/ros.h"
28 #include "ros/console.h"
31 #include "tf/transform_listener.h"
32 #include "tf/message_filter.h"
33 #include "visualization_msgs/MarkerArray.h"
34 
35 #include "nav_msgs/MapMetaData.h"
36 #include "sensor_msgs/LaserScan.h"
37 #include "nav_msgs/GetMap.h"
38 
39 #include "open_karto/Mapper.h"
40 
41 #include "spa_solver.h"
42 
43 #include <boost/thread.hpp>
44 
45 #include <string>
46 #include <map>
47 #include <vector>
48 
49 // compute linear index for given map coords
50 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
51 
52 class SlamKarto
53 {
54  public:
55  SlamKarto();
56  ~SlamKarto();
57 
58  void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan);
59  bool mapCallback(nav_msgs::GetMap::Request &req,
60  nav_msgs::GetMap::Response &res);
61 
62  private:
63  bool getOdomPose(karto::Pose2& karto_pose, const ros::Time& t);
64  karto::LaserRangeFinder* getLaser(const sensor_msgs::LaserScan::ConstPtr& scan);
65  bool addScan(karto::LaserRangeFinder* laser,
66  const sensor_msgs::LaserScan::ConstPtr& scan,
67  karto::Pose2& karto_pose);
68  bool updateMap();
69  void publishTransform();
70  void publishLoop(double transform_publish_period);
72 
73  // ROS handles
83 
84  // The map that will be published / send to service callers
85  nav_msgs::GetMap::Response map_;
86 
87  // Storage for ROS parameters
88  std::string odom_frame_;
89  std::string map_frame_;
90  std::string base_frame_;
93  double resolution_;
94  boost::mutex map_mutex_;
95  boost::mutex map_to_odom_mutex_;
96 
97  // Karto bookkeeping
101  std::map<std::string, karto::LaserRangeFinder*> lasers_;
102  std::map<std::string, bool> lasers_inverted_;
103 
104  // Internal state
105  bool got_map_;
107  boost::thread* transform_thread_;
109  unsigned marker_count_;
111 };
112 
114  got_map_(false),
115  laser_count_(0),
116  transform_thread_(NULL),
117  marker_count_(0)
118 {
120  // Retrieve parameters
121  ros::NodeHandle private_nh_("~");
122  if(!private_nh_.getParam("odom_frame", odom_frame_))
123  odom_frame_ = "odom";
124  if(!private_nh_.getParam("map_frame", map_frame_))
125  map_frame_ = "map";
126  if(!private_nh_.getParam("base_frame", base_frame_))
127  base_frame_ = "base_link";
128  if(!private_nh_.getParam("throttle_scans", throttle_scans_))
129  throttle_scans_ = 1;
130  double tmp;
131  if(!private_nh_.getParam("map_update_interval", tmp))
132  tmp = 5.0;
134  if(!private_nh_.getParam("resolution", resolution_))
135  {
136  // Compatibility with slam_gmapping, which uses "delta" to mean
137  // resolution
138  if(!private_nh_.getParam("delta", resolution_))
139  resolution_ = 0.05;
140  }
141  double transform_publish_period;
142  private_nh_.param("transform_publish_period", transform_publish_period, 0.05);
143 
144  // Set up advertisements and subscriptions
146  sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
147  sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
148  ss_ = node_.advertiseService("dynamic_map", &SlamKarto::mapCallback, this);
151  scan_filter_->registerCallback(boost::bind(&SlamKarto::laserCallback, this, _1));
152  marker_publisher_ = node_.advertise<visualization_msgs::MarkerArray>("visualization_marker_array",1);
153 
154  // Create a thread to periodically publish the latest map->odom
155  // transform; it needs to go out regularly, uninterrupted by potentially
156  // long periods of computation in our main loop.
157  transform_thread_ = new boost::thread(boost::bind(&SlamKarto::publishLoop, this, transform_publish_period));
158 
159  // Initialize Karto structures
160  mapper_ = new karto::Mapper();
161  dataset_ = new karto::Dataset();
162 
163  // Setting General Parameters from the Parameter Server
164  bool use_scan_matching;
165  if(private_nh_.getParam("use_scan_matching", use_scan_matching))
166  mapper_->setParamUseScanMatching(use_scan_matching);
167 
168  bool use_scan_barycenter;
169  if(private_nh_.getParam("use_scan_barycenter", use_scan_barycenter))
170  mapper_->setParamUseScanBarycenter(use_scan_barycenter);
171 
172  double minimum_travel_distance;
173  if(private_nh_.getParam("minimum_travel_distance", minimum_travel_distance))
174  mapper_->setParamMinimumTravelDistance(minimum_travel_distance);
175 
176  double minimum_travel_heading;
177  if(private_nh_.getParam("minimum_travel_heading", minimum_travel_heading))
178  mapper_->setParamMinimumTravelHeading(minimum_travel_heading);
179 
180  int scan_buffer_size;
181  if(private_nh_.getParam("scan_buffer_size", scan_buffer_size))
182  mapper_->setParamScanBufferSize(scan_buffer_size);
183 
184  double scan_buffer_maximum_scan_distance;
185  if(private_nh_.getParam("scan_buffer_maximum_scan_distance", scan_buffer_maximum_scan_distance))
186  mapper_->setParamScanBufferMaximumScanDistance(scan_buffer_maximum_scan_distance);
187 
188  double link_match_minimum_response_fine;
189  if(private_nh_.getParam("link_match_minimum_response_fine", link_match_minimum_response_fine))
190  mapper_->setParamLinkMatchMinimumResponseFine(link_match_minimum_response_fine);
191 
192  double link_scan_maximum_distance;
193  if(private_nh_.getParam("link_scan_maximum_distance", link_scan_maximum_distance))
194  mapper_->setParamLinkScanMaximumDistance(link_scan_maximum_distance);
195 
196  double loop_search_maximum_distance;
197  if(private_nh_.getParam("loop_search_maximum_distance", loop_search_maximum_distance))
198  mapper_->setParamLoopSearchMaximumDistance(loop_search_maximum_distance);
199 
200  bool do_loop_closing;
201  if(private_nh_.getParam("do_loop_closing", do_loop_closing))
202  mapper_->setParamDoLoopClosing(do_loop_closing);
203 
204  int loop_match_minimum_chain_size;
205  if(private_nh_.getParam("loop_match_minimum_chain_size", loop_match_minimum_chain_size))
206  mapper_->setParamLoopMatchMinimumChainSize(loop_match_minimum_chain_size);
207 
208  double loop_match_maximum_variance_coarse;
209  if(private_nh_.getParam("loop_match_maximum_variance_coarse", loop_match_maximum_variance_coarse))
210  mapper_->setParamLoopMatchMaximumVarianceCoarse(loop_match_maximum_variance_coarse);
211 
212  double loop_match_minimum_response_coarse;
213  if(private_nh_.getParam("loop_match_minimum_response_coarse", loop_match_minimum_response_coarse))
214  mapper_->setParamLoopMatchMinimumResponseCoarse(loop_match_minimum_response_coarse);
215 
216  double loop_match_minimum_response_fine;
217  if(private_nh_.getParam("loop_match_minimum_response_fine", loop_match_minimum_response_fine))
218  mapper_->setParamLoopMatchMinimumResponseFine(loop_match_minimum_response_fine);
219 
220  // Setting Correlation Parameters from the Parameter Server
221 
222  double correlation_search_space_dimension;
223  if(private_nh_.getParam("correlation_search_space_dimension", correlation_search_space_dimension))
224  mapper_->setParamCorrelationSearchSpaceDimension(correlation_search_space_dimension);
225 
226  double correlation_search_space_resolution;
227  if(private_nh_.getParam("correlation_search_space_resolution", correlation_search_space_resolution))
228  mapper_->setParamCorrelationSearchSpaceResolution(correlation_search_space_resolution);
229 
230  double correlation_search_space_smear_deviation;
231  if(private_nh_.getParam("correlation_search_space_smear_deviation", correlation_search_space_smear_deviation))
232  mapper_->setParamCorrelationSearchSpaceSmearDeviation(correlation_search_space_smear_deviation);
233 
234  // Setting Correlation Parameters, Loop Closure Parameters from the Parameter Server
235 
236  double loop_search_space_dimension;
237  if(private_nh_.getParam("loop_search_space_dimension", loop_search_space_dimension))
238  mapper_->setParamLoopSearchSpaceDimension(loop_search_space_dimension);
239 
240  double loop_search_space_resolution;
241  if(private_nh_.getParam("loop_search_space_resolution", loop_search_space_resolution))
242  mapper_->setParamLoopSearchSpaceResolution(loop_search_space_resolution);
243 
244  double loop_search_space_smear_deviation;
245  if(private_nh_.getParam("loop_search_space_smear_deviation", loop_search_space_smear_deviation))
246  mapper_->setParamLoopSearchSpaceSmearDeviation(loop_search_space_smear_deviation);
247 
248  // Setting Scan Matcher Parameters from the Parameter Server
249 
250  double distance_variance_penalty;
251  if(private_nh_.getParam("distance_variance_penalty", distance_variance_penalty))
252  mapper_->setParamDistanceVariancePenalty(distance_variance_penalty);
253 
254  double angle_variance_penalty;
255  if(private_nh_.getParam("angle_variance_penalty", angle_variance_penalty))
256  mapper_->setParamAngleVariancePenalty(angle_variance_penalty);
257 
258  double fine_search_angle_offset;
259  if(private_nh_.getParam("fine_search_angle_offset", fine_search_angle_offset))
260  mapper_->setParamFineSearchAngleOffset(fine_search_angle_offset);
261 
262  double coarse_search_angle_offset;
263  if(private_nh_.getParam("coarse_search_angle_offset", coarse_search_angle_offset))
264  mapper_->setParamCoarseSearchAngleOffset(coarse_search_angle_offset);
265 
266  double coarse_angle_resolution;
267  if(private_nh_.getParam("coarse_angle_resolution", coarse_angle_resolution))
268  mapper_->setParamCoarseAngleResolution(coarse_angle_resolution);
269 
270  double minimum_angle_penalty;
271  if(private_nh_.getParam("minimum_angle_penalty", minimum_angle_penalty))
272  mapper_->setParamMinimumAnglePenalty(minimum_angle_penalty);
273 
274  double minimum_distance_penalty;
275  if(private_nh_.getParam("minimum_distance_penalty", minimum_distance_penalty))
276  mapper_->setParamMinimumDistancePenalty(minimum_distance_penalty);
277 
278  bool use_response_expansion;
279  if(private_nh_.getParam("use_response_expansion", use_response_expansion))
280  mapper_->setParamUseResponseExpansion(use_response_expansion);
281 
282  // Set solver to be used in loop closure
283  solver_ = new SpaSolver();
285 }
286 
288 {
290  {
291  transform_thread_->join();
292  delete transform_thread_;
293  }
294  if (scan_filter_)
295  delete scan_filter_;
296  if (scan_filter_sub_)
297  delete scan_filter_sub_;
298  if (solver_)
299  delete solver_;
300  if (mapper_)
301  delete mapper_;
302  if (dataset_)
303  delete dataset_;
304  // TODO: delete the pointers in the lasers_ map; not sure whether or not
305  // I'm supposed to do that.
306 }
307 
308 void
309 SlamKarto::publishLoop(double transform_publish_period)
310 {
311  if(transform_publish_period == 0)
312  return;
313 
314  ros::Rate r(1.0 / transform_publish_period);
315  while(ros::ok())
316  {
318  r.sleep();
319  }
320 }
321 
322 void
324 {
325  boost::mutex::scoped_lock lock(map_to_odom_mutex_);
326  ros::Time tf_expiration = ros::Time::now() + ros::Duration(0.05);
328 }
329 
331 SlamKarto::getLaser(const sensor_msgs::LaserScan::ConstPtr& scan)
332 {
333  // Check whether we know about this laser yet
334  if(lasers_.find(scan->header.frame_id) == lasers_.end())
335  {
336  // New laser; need to create a Karto device for it.
337 
338  // Get the laser's pose, relative to base.
339  tf::Stamped<tf::Pose> ident;
340  tf::Stamped<tf::Transform> laser_pose;
341  ident.setIdentity();
342  ident.frame_id_ = scan->header.frame_id;
343  ident.stamp_ = scan->header.stamp;
344  try
345  {
346  tf_.transformPose(base_frame_, ident, laser_pose);
347  }
348  catch(tf::TransformException e)
349  {
350  ROS_WARN("Failed to compute laser pose, aborting initialization (%s)",
351  e.what());
352  return NULL;
353  }
354 
355  double yaw = tf::getYaw(laser_pose.getRotation());
356 
357  ROS_INFO("laser %s's pose wrt base: %.3f %.3f %.3f",
358  scan->header.frame_id.c_str(),
359  laser_pose.getOrigin().x(),
360  laser_pose.getOrigin().y(),
361  yaw);
362  // To account for lasers that are mounted upside-down,
363  // we create a point 1m above the laser and transform it into the laser frame
364  // if the point's z-value is <=0, it is upside-down
365 
366  tf::Vector3 v;
367  v.setValue(0, 0, 1 + laser_pose.getOrigin().z());
368  tf::Stamped<tf::Vector3> up(v, scan->header.stamp, base_frame_);
369 
370  try
371  {
372  tf_.transformPoint(scan->header.frame_id, up, up);
373  ROS_DEBUG("Z-Axis in sensor frame: %.3f", up.z());
374  }
375  catch (tf::TransformException& e)
376  {
377  ROS_WARN("Unable to determine orientation of laser: %s", e.what());
378  return NULL;
379  }
380 
381  bool inverse = lasers_inverted_[scan->header.frame_id] = up.z() <= 0;
382  if (inverse)
383  ROS_INFO("laser is mounted upside-down");
384 
385 
386  // Create a laser range finder device and copy in data from the first
387  // scan
388  std::string name = scan->header.frame_id;
389  karto::LaserRangeFinder* laser =
391  laser->SetOffsetPose(karto::Pose2(laser_pose.getOrigin().x(),
392  laser_pose.getOrigin().y(),
393  yaw));
394  laser->SetMinimumRange(scan->range_min);
395  laser->SetMaximumRange(scan->range_max);
396  laser->SetMinimumAngle(scan->angle_min);
397  laser->SetMaximumAngle(scan->angle_max);
398  laser->SetAngularResolution(scan->angle_increment);
399  // TODO: expose this, and many other parameters
400  //laser_->SetRangeThreshold(12.0);
401 
402  // Store this laser device for later
403  lasers_[scan->header.frame_id] = laser;
404 
405  // Add it to the dataset, which seems to be necessary
406  dataset_->Add(laser);
407  }
408 
409  return lasers_[scan->header.frame_id];
410 }
411 
412 bool
414 {
415  // Get the robot's pose
417  tf::Vector3(0,0,0)), t, base_frame_);
418  tf::Stamped<tf::Transform> odom_pose;
419  try
420  {
421  tf_.transformPose(odom_frame_, ident, odom_pose);
422  }
423  catch(tf::TransformException e)
424  {
425  ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
426  return false;
427  }
428  double yaw = tf::getYaw(odom_pose.getRotation());
429 
430  karto_pose =
431  karto::Pose2(odom_pose.getOrigin().x(),
432  odom_pose.getOrigin().y(),
433  yaw);
434  return true;
435 }
436 
437 void
439 {
440  std::vector<float> graph;
441  solver_->getGraph(graph);
442 
443  visualization_msgs::MarkerArray marray;
444 
445  visualization_msgs::Marker m;
446  m.header.frame_id = "map";
447  m.header.stamp = ros::Time::now();
448  m.id = 0;
449  m.ns = "karto";
450  m.type = visualization_msgs::Marker::SPHERE;
451  m.pose.position.x = 0.0;
452  m.pose.position.y = 0.0;
453  m.pose.position.z = 0.0;
454  m.scale.x = 0.1;
455  m.scale.y = 0.1;
456  m.scale.z = 0.1;
457  m.color.r = 1.0;
458  m.color.g = 0;
459  m.color.b = 0.0;
460  m.color.a = 1.0;
461  m.lifetime = ros::Duration(0);
462 
463  visualization_msgs::Marker edge;
464  edge.header.frame_id = "map";
465  edge.header.stamp = ros::Time::now();
466  edge.action = visualization_msgs::Marker::ADD;
467  edge.ns = "karto";
468  edge.id = 0;
469  edge.type = visualization_msgs::Marker::LINE_STRIP;
470  edge.scale.x = 0.1;
471  edge.scale.y = 0.1;
472  edge.scale.z = 0.1;
473  edge.color.a = 1.0;
474  edge.color.r = 0.0;
475  edge.color.g = 0.0;
476  edge.color.b = 1.0;
477 
478  m.action = visualization_msgs::Marker::ADD;
479  uint id = 0;
480  for (uint i=0; i<graph.size()/2; i++)
481  {
482  m.id = id;
483  m.pose.position.x = graph[2*i];
484  m.pose.position.y = graph[2*i+1];
485  marray.markers.push_back(visualization_msgs::Marker(m));
486  id++;
487 
488  if(i>0)
489  {
490  edge.points.clear();
491 
492  geometry_msgs::Point p;
493  p.x = graph[2*(i-1)];
494  p.y = graph[2*(i-1)+1];
495  edge.points.push_back(p);
496  p.x = graph[2*i];
497  p.y = graph[2*i+1];
498  edge.points.push_back(p);
499  edge.id = id;
500 
501  marray.markers.push_back(visualization_msgs::Marker(edge));
502  id++;
503  }
504  }
505 
506  m.action = visualization_msgs::Marker::DELETE;
507  for (; id < marker_count_; id++)
508  {
509  m.id = id;
510  marray.markers.push_back(visualization_msgs::Marker(m));
511  }
512 
513  marker_count_ = marray.markers.size();
514 
515  marker_publisher_.publish(marray);
516 }
517 
518 void
519 SlamKarto::laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
520 {
521  laser_count_++;
522  if ((laser_count_ % throttle_scans_) != 0)
523  return;
524 
525  static ros::Time last_map_update(0,0);
526 
527  // Check whether we know about this laser yet
528  karto::LaserRangeFinder* laser = getLaser(scan);
529 
530  if(!laser)
531  {
532  ROS_WARN("Failed to create laser device for %s; discarding scan",
533  scan->header.frame_id.c_str());
534  return;
535  }
536 
537  karto::Pose2 odom_pose;
538  if(addScan(laser, scan, odom_pose))
539  {
540  ROS_DEBUG("added scan at pose: %.3f %.3f %.3f",
541  odom_pose.GetX(),
542  odom_pose.GetY(),
543  odom_pose.GetHeading());
544 
546 
547  if(!got_map_ ||
548  (scan->header.stamp - last_map_update) > map_update_interval_)
549  {
550  if(updateMap())
551  {
552  last_map_update = scan->header.stamp;
553  got_map_ = true;
554  ROS_DEBUG("Updated the map");
555  }
556  }
557  }
558 }
559 
560 bool
562 {
563  boost::mutex::scoped_lock lock(map_mutex_);
564 
565  karto::OccupancyGrid* occ_grid =
567 
568  if(!occ_grid)
569  return false;
570 
571  if(!got_map_) {
572  map_.map.info.resolution = resolution_;
573  map_.map.info.origin.position.x = 0.0;
574  map_.map.info.origin.position.y = 0.0;
575  map_.map.info.origin.position.z = 0.0;
576  map_.map.info.origin.orientation.x = 0.0;
577  map_.map.info.origin.orientation.y = 0.0;
578  map_.map.info.origin.orientation.z = 0.0;
579  map_.map.info.origin.orientation.w = 1.0;
580  }
581 
582  // Translate to ROS format
583  kt_int32s width = occ_grid->GetWidth();
584  kt_int32s height = occ_grid->GetHeight();
585  karto::Vector2<kt_double> offset = occ_grid->GetCoordinateConverter()->GetOffset();
586 
587  if(map_.map.info.width != (unsigned int) width ||
588  map_.map.info.height != (unsigned int) height ||
589  map_.map.info.origin.position.x != offset.GetX() ||
590  map_.map.info.origin.position.y != offset.GetY())
591  {
592  map_.map.info.origin.position.x = offset.GetX();
593  map_.map.info.origin.position.y = offset.GetY();
594  map_.map.info.width = width;
595  map_.map.info.height = height;
596  map_.map.data.resize(map_.map.info.width * map_.map.info.height);
597  }
598 
599  for (kt_int32s y=0; y<height; y++)
600  {
601  for (kt_int32s x=0; x<width; x++)
602  {
603  // Getting the value at position x,y
604  kt_int8u value = occ_grid->GetValue(karto::Vector2<kt_int32s>(x, y));
605 
606  switch (value)
607  {
609  map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = -1;
610  break;
612  map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 100;
613  break;
615  map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 0;
616  break;
617  default:
618  ROS_WARN("Encountered unknown cell value at %d, %d", x, y);
619  break;
620  }
621  }
622  }
623 
624  // Set the header information on the map
625  map_.map.header.stamp = ros::Time::now();
626  map_.map.header.frame_id = map_frame_;
627 
628  sst_.publish(map_.map);
629  sstm_.publish(map_.map.info);
630 
631  delete occ_grid;
632 
633  return true;
634 }
635 
636 bool
638  const sensor_msgs::LaserScan::ConstPtr& scan,
639  karto::Pose2& karto_pose)
640 {
641  if(!getOdomPose(karto_pose, scan->header.stamp))
642  return false;
643 
644  // Create a vector of doubles for karto
645  std::vector<kt_double> readings;
646 
647  if (lasers_inverted_[scan->header.frame_id]) {
648  for(std::vector<float>::const_reverse_iterator it = scan->ranges.rbegin();
649  it != scan->ranges.rend();
650  ++it)
651  {
652  readings.push_back(*it);
653  }
654  } else {
655  for(std::vector<float>::const_iterator it = scan->ranges.begin();
656  it != scan->ranges.end();
657  ++it)
658  {
659  readings.push_back(*it);
660  }
661  }
662 
663  // create localized range scan
664  karto::LocalizedRangeScan* range_scan =
665  new karto::LocalizedRangeScan(laser->GetName(), readings);
666  range_scan->SetOdometricPose(karto_pose);
667  range_scan->SetCorrectedPose(karto_pose);
668 
669  // Add the localized range scan to the mapper
670  bool processed;
671  if((processed = mapper_->Process(range_scan)))
672  {
673  //std::cout << "Pose: " << range_scan->GetOdometricPose() << " Corrected Pose: " << range_scan->GetCorrectedPose() << std::endl;
674 
675  karto::Pose2 corrected_pose = range_scan->GetCorrectedPose();
676 
677  // Compute the map->odom transform
678  tf::Stamped<tf::Pose> odom_to_map;
679  try
680  {
682  tf::Vector3(corrected_pose.GetX(), corrected_pose.GetY(), 0.0)).inverse(),
683  scan->header.stamp, base_frame_),odom_to_map);
684  }
685  catch(tf::TransformException e)
686  {
687  ROS_ERROR("Transform from base_link to odom failed\n");
688  odom_to_map.setIdentity();
689  }
690 
691  map_to_odom_mutex_.lock();
692  map_to_odom_ = tf::Transform(tf::Quaternion( odom_to_map.getRotation() ),
693  tf::Point( odom_to_map.getOrigin() ) ).inverse();
694  map_to_odom_mutex_.unlock();
695 
696 
697  // Add the localized range scan to the dataset (for memory management)
698  dataset_->Add(range_scan);
699  }
700  else
701  delete range_scan;
702 
703  return processed;
704 }
705 
706 bool
707 SlamKarto::mapCallback(nav_msgs::GetMap::Request &req,
708  nav_msgs::GetMap::Response &res)
709 {
710  boost::mutex::scoped_lock lock(map_mutex_);
711  if(got_map_ && map_.map.info.width && map_.map.info.height)
712  {
713  res = map_;
714  return true;
715  }
716  else
717  return false;
718 }
719 
720 int
721 main(int argc, char** argv)
722 {
723  ros::init(argc, argv, "slam_karto");
724 
725  SlamKarto kn;
726 
727  ros::spin();
728 
729  return 0;
730 }
kt_int32s GetHeight() const
virtual kt_bool Process(LocalizedRangeScan *pScan)
int32_t kt_int32s
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
void setParamCorrelationSearchSpaceResolution(double d)
void setParamLoopMatchMinimumChainSize(int i)
bool got_map_
Definition: slam_karto.cpp:105
kt_double GetHeading() const
int main(int argc, char **argv)
Definition: slam_karto.cpp:721
SpaSolver * solver_
Definition: slam_karto.cpp:100
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle node_
Definition: slam_karto.cpp:74
void setParamUseScanMatching(bool b)
const T & GetY() const
static double getYaw(const Quaternion &bt_q)
uint8_t kt_int8u
ros::Publisher marker_publisher_
Definition: slam_karto.cpp:80
kt_double GetX() const
GridStates_Occupied
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setParamDoLoopClosing(bool b)
Pose2(const Pose3 &rPose)
void setParamCorrelationSearchSpaceSmearDeviation(double d)
unsigned marker_count_
Definition: slam_karto.cpp:109
int laser_count_
Definition: slam_karto.cpp:106
GridStates_Unknown
kt_int32s GetWidth() const
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
void setParamDistanceVariancePenalty(double d)
std::map< std::string, bool > lasers_inverted_
Definition: slam_karto.cpp:102
const Name & GetName() const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
Definition: slam_karto.cpp:77
void setParamScanBufferSize(int i)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void setParamCorrelationSearchSpaceDimension(double d)
#define ROS_WARN(...)
void SetMinimumAngle(kt_double minimumAngle)
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z)
std::string map_frame_
Definition: slam_karto.cpp:89
void SetMaximumRange(kt_double maximumRange)
void SetOffsetPose(const Pose2 &rPose)
LaserRangeFinder_Custom
ROSCPP_DECL void spin(Spinner &spinner)
void setIdentity()
void setParamAngleVariancePenalty(double d)
karto::Mapper * mapper_
Definition: slam_karto.cpp:98
void publishGraphVisualization()
Definition: slam_karto.cpp:438
ros::Publisher sst_
Definition: slam_karto.cpp:79
const T & GetX() const
bool inverted_laser_
Definition: slam_karto.cpp:110
void setParamLoopMatchMaximumVarianceCoarse(double d)
void SetAngularResolution(kt_double angularResolution)
void Add(Object *pObject)
void setParamLinkScanMaximumDistance(double d)
void setParamMinimumAnglePenalty(double d)
tf::Transform map_to_odom_
Definition: slam_karto.cpp:108
void SetMaximumAngle(kt_double maximumAngle)
Duration & fromSec(double t)
bool getOdomPose(karto::Pose2 &karto_pose, const ros::Time &t)
Definition: slam_karto.cpp:413
#define ROS_INFO(...)
double resolution_
Definition: slam_karto.cpp:93
ros::Publisher sstm_
Definition: slam_karto.cpp:81
void setParamLoopSearchSpaceDimension(double d)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void setParamLoopSearchSpaceResolution(double d)
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
std::map< std::string, karto::LaserRangeFinder * > lasers_
Definition: slam_karto.cpp:101
void setParamScanBufferMaximumScanDistance(double d)
void setParamMinimumDistancePenalty(double d)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: slam_karto.cpp:707
ros::Duration map_update_interval_
Definition: slam_karto.cpp:92
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: slam_karto.cpp:519
void setParamLoopSearchMaximumDistance(double d)
TFSIMD_FORCE_INLINE const tfScalar & x() const
karto::Dataset * dataset_
Definition: slam_karto.cpp:99
Transform inverse() const
void setParamLoopMatchMinimumResponseCoarse(double d)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setParamMinimumTravelDistance(double d)
tf::TransformBroadcaster * tfB_
Definition: slam_karto.cpp:76
static OccupancyGrid * CreateFromScans(const LocalizedRangeScanVector &rScans, kt_double resolution)
void SetScanSolver(ScanSolver *pSolver)
bool sleep()
virtual const LocalizedRangeScanVector GetAllProcessedScans() const
void SetOdometricPose(const Pose2 &rPose)
ros::Time stamp_
std::string odom_frame_
Definition: slam_karto.cpp:88
static LaserRangeFinder * CreateLaserRangeFinder(LaserRangeFinderType type, const Name &rName)
void publishTransform()
Definition: slam_karto.cpp:323
void setParamLinkMatchMinimumResponseFine(double d)
int throttle_scans_
Definition: slam_karto.cpp:91
bool addScan(karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
Definition: slam_karto.cpp:637
std::string frame_id_
CoordinateConverter * GetCoordinateConverter() const
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
void setParamCoarseSearchAngleOffset(double d)
void SetMinimumRange(kt_double minimumRange)
boost::mutex map_to_odom_mutex_
Definition: slam_karto.cpp:95
karto::LaserRangeFinder * getLaser(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: slam_karto.cpp:331
void SetCorrectedPose(const Pose2 &rPose)
void setParamFineSearchAngleOffset(double d)
bool getParam(const std::string &key, std::string &s) const
boost::mutex map_mutex_
Definition: slam_karto.cpp:94
#define MAP_IDX(sx, i, j)
Definition: slam_karto.cpp:50
void publishLoop(double transform_publish_period)
Definition: slam_karto.cpp:309
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
Definition: slam_karto.cpp:78
tf::TransformListener tf_
Definition: slam_karto.cpp:75
kt_int8u GetValue(const Vector2< kt_int32s > &rGrid) const
static Time now()
nav_msgs::GetMap::Response map_
Definition: slam_karto.cpp:85
kt_double GetY() const
void setParamMinimumTravelHeading(double d)
void setParamUseResponseExpansion(bool b)
void setParamLoopMatchMinimumResponseFine(double d)
void setParamUseScanBarycenter(bool b)
#define ROS_ERROR(...)
std::string base_frame_
Definition: slam_karto.cpp:90
const Pose2 & GetCorrectedPose() const
GridStates_Free
boost::thread * transform_thread_
Definition: slam_karto.cpp:107
void setParamLoopSearchSpaceSmearDeviation(double d)
bool updateMap()
Definition: slam_karto.cpp:561
Connection registerCallback(const C &callback)
#define ROS_DEBUG(...)
void setParamCoarseAngleResolution(double d)
ros::ServiceServer ss_
Definition: slam_karto.cpp:82


slam_karto
Author(s): Brian Gerkey
autogenerated on Mon Jun 10 2019 15:08:17