slam_toolbox_common.cpp
Go to the documentation of this file.
1 /*
2  * slam_toolbox
3  * Copyright Work Modifications (c) 2018, Simbe Robotics, Inc.
4  * Copyright Work Modifications (c) 2019, Samsung Research America
5  *
6  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
7  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
8  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
9  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
10  *
11  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
12  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
13  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
14  * CONDITIONS.
15  *
16  */
17 
18 /* Orginal Author for slam_karto the original work was based on: Brian Gerkey */
19 /* Author: Steven Macenski */
20 
23 
24 namespace slam_toolbox
25 {
26 
27 /*****************************************************************************/
29 : solver_loader_("slam_toolbox", "karto::ScanSolver"),
30  processor_type_(PROCESS),
31  first_measurement_(true),
32  nh_(nh),
33  process_near_pose_(nullptr)
34 /*****************************************************************************/
35 {
36  smapper_ = std::make_unique<mapper_utils::SMapper>();
37  dataset_ = std::make_unique<karto::Dataset>();
38 
39  setParams(nh_);
41  setSolver(nh_);
42 
43  laser_assistant_ = std::make_unique<laser_utils::LaserAssistant>(
44  nh_, tf_.get(), base_frame_);
45  pose_helper_ = std::make_unique<pose_utils::GetPoseHelper>(
46  tf_.get(), base_frame_, odom_frame_);
47  scan_holder_ = std::make_unique<laser_utils::ScanHolder>(lasers_);
48  map_saver_ = std::make_unique<map_saver::MapSaver>(nh_, map_name_);
50  std::make_unique<loop_closure_assistant::LoopClosureAssistant>(
51  nh_, smapper_->getMapper(), scan_holder_.get(), state_, processor_type_);
52 
54 
55  double transform_publish_period;
56  nh_.param("transform_publish_period", transform_publish_period, 0.05);
57  threads_.push_back(std::make_unique<boost::thread>(
59  this, transform_publish_period)));
60  threads_.push_back(std::make_unique<boost::thread>(
61  boost::bind(&SlamToolbox::publishVisualizations, this)));
62 }
63 
64 /*****************************************************************************/
66 /*****************************************************************************/
67 {
68  for (int i=0; i != threads_.size(); i++)
69  {
70  threads_[i]->join();
71  }
72 
73  smapper_.reset();
74  dataset_.reset();
75  closure_assistant_.reset();
76  map_saver_.reset();
77  pose_helper_.reset();
78  laser_assistant_.reset();
79  scan_holder_.reset();
80 }
81 
82 /*****************************************************************************/
84 /*****************************************************************************/
85 {
86  // Set solver to be used in loop closure
87  std::string solver_plugin;
88  if(!private_nh_.getParam("solver_plugin", solver_plugin))
89  {
90  ROS_WARN("unable to find requested solver plugin, defaulting to SPA");
91  solver_plugin = "solver_plugins::CeresSolver";
92  }
93  try
94  {
95  solver_ = solver_loader_.createInstance(solver_plugin);
96  ROS_INFO("Using plugin %s", solver_plugin.c_str());
97  }
98  catch (const pluginlib::PluginlibException& ex)
99  {
100  ROS_FATAL("Failed to create %s, is it registered and built? Exception: %s.",
101  solver_plugin.c_str(), ex.what());
102  exit(1);
103  }
104  smapper_->getMapper()->SetScanSolver(solver_.get());
105 }
106 
107 /*****************************************************************************/
109 /*****************************************************************************/
110 {
112  private_nh.param("odom_frame", odom_frame_, std::string("odom"));
113  private_nh.param("map_frame", map_frame_, std::string("map"));
114  private_nh.param("base_frame", base_frame_, std::string("base_footprint"));
115  private_nh.param("resolution", resolution_, 0.05);
116  private_nh.param("map_name", map_name_, std::string("/map"));
117  private_nh.param("scan_topic", scan_topic_, std::string("/scan"));
118  private_nh.param("throttle_scans", throttle_scans_, 1);
119  private_nh.param("enable_interactive_mode", enable_interactive_mode_, false);
120 
121  double tmp_val;
122  private_nh.param("transform_timeout", tmp_val, 0.2);
124  private_nh.param("tf_buffer_duration", tmp_val, 30.);
125  tf_buffer_dur_ = ros::Duration(tmp_val);
126  private_nh.param("minimum_time_interval", tmp_val, 0.5);
128 
129  private_nh.param("position_covariance_scale", position_covariance_scale_, 1.0);
130  private_nh.param("yaw_covariance_scale", yaw_covariance_scale_, 1.0);
131 
132  bool debug = false;
133  if (private_nh.getParam("debug_logging", debug) && debug)
134  {
137  {
139  }
140  }
141 
142  smapper_->configure(private_nh);
143  private_nh.setParam("paused_new_measurements", false);
144 }
145 
146 /*****************************************************************************/
148 /*****************************************************************************/
149 {
150  tf_ = std::make_unique<tf2_ros::Buffer>(ros::Duration(tf_buffer_dur_));
151  tfL_ = std::make_unique<tf2_ros::TransformListener>(*tf_);
152  tfB_ = std::make_unique<tf2_ros::TransformBroadcaster>();
153  sst_ = node.advertise<nav_msgs::OccupancyGrid>(map_name_, 1, true);
154  sstm_ = node.advertise<nav_msgs::MapMetaData>(map_name_ + "_metadata", 1, true);
155  ssMap_ = node.advertiseService("dynamic_map", &SlamToolbox::mapCallback, this);
159  ssReset_ = node.advertiseService("reset", &SlamToolbox::resetCallback, this);
160  scan_filter_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::LaserScan> >(node, scan_topic_, 5);
161  scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::LaserScan> >(*scan_filter_sub_, *tf_, odom_frame_, 5, node);
162  scan_filter_->registerCallback(boost::bind(&SlamToolbox::laserCallback, this, _1));
163  pose_pub_ = node.advertise<geometry_msgs::PoseWithCovarianceStamped>("pose", 10, true);
164 }
165 
166 /*****************************************************************************/
167 void SlamToolbox::publishTransformLoop(const double& transform_publish_period)
168 /*****************************************************************************/
169 {
170  if(transform_publish_period == 0)
171  {
172  return;
173  }
174 
175  ros::Rate r(1.0 / transform_publish_period);
176  while(ros::ok())
177  {
178  {
179  boost::mutex::scoped_lock lock(map_to_odom_mutex_);
180  geometry_msgs::TransformStamped msg;
181  tf2::convert(map_to_odom_, msg.transform);
182  msg.child_frame_id = odom_frame_;
183  msg.header.frame_id = map_frame_;
184  msg.header.stamp = ros::Time::now() + transform_timeout_;
185  tfB_->sendTransform(msg);
186  }
187  r.sleep();
188  }
189 }
190 
191 /*****************************************************************************/
193 /*****************************************************************************/
194 {
195  nav_msgs::OccupancyGrid& og = map_.map;
196  og.info.resolution = resolution_;
197  og.info.origin.position.x = 0.0;
198  og.info.origin.position.y = 0.0;
199  og.info.origin.position.z = 0.0;
200  og.info.origin.orientation.x = 0.0;
201  og.info.origin.orientation.y = 0.0;
202  og.info.origin.orientation.z = 0.0;
203  og.info.origin.orientation.w = 1.0;
204  og.header.frame_id = map_frame_;
205 
206  double map_update_interval;
207  if(!nh_.getParam("map_update_interval", map_update_interval))
208  map_update_interval = 10.0;
209  ros::Rate r(1.0 / map_update_interval);
210 
211  while(ros::ok())
212  {
213  updateMap();
215  {
216  boost::mutex::scoped_lock lock(smapper_mutex_);
217  closure_assistant_->publishGraph();
218  }
219  r.sleep();
220  }
221 }
222 
223 /*****************************************************************************/
225 /*****************************************************************************/
226 {
227  std::string filename;
228  geometry_msgs::Pose2D pose;
229  bool dock = false;
230  if (shouldStartWithPoseGraph(filename, pose, dock))
231  {
232  slam_toolbox_msgs::DeserializePoseGraph::Request req;
233  slam_toolbox_msgs::DeserializePoseGraph::Response resp;
234  req.initial_pose = pose;
235  req.filename = filename;
236  if (dock)
237  {
238  req.match_type =
239  slam_toolbox_msgs::DeserializePoseGraph::Request::START_AT_FIRST_NODE;
240  }
241  else
242  {
243  req.match_type =
244  slam_toolbox_msgs::DeserializePoseGraph::Request::START_AT_GIVEN_POSE;
245  }
246  deserializePoseGraphCallback(req, resp);
247  }
248 }
249 
250 /*****************************************************************************/
252  geometry_msgs::Pose2D& pose, bool& start_at_dock)
253 /*****************************************************************************/
254  {
255  // if given a map to load at run time, do it.
256  if (nh_.getParam("map_file_name", filename))
257  {
258  std::vector<double> read_pose;
259  if (nh_.getParam("map_start_pose", read_pose))
260  {
261  start_at_dock = false;
262  if (read_pose.size() != 3)
263  {
264  ROS_ERROR("LocalizationSlamToolbox: Incorrect number of "
265  "arguments for map starting pose. Must be in format: "
266  "[x, y, theta]. Starting at the origin");
267  pose.x = 0.;
268  pose.y = 0.;
269  pose.theta = 0.;
270  }
271  else
272  {
273  pose.x = read_pose[0];
274  pose.y = read_pose[1];
275  pose.theta = read_pose[2];
276  }
277  }
278  else
279  {
280  nh_.getParam("map_start_at_dock", start_at_dock);
281  }
282 
283  return true;
284  }
285 
286  return false;
287 }
288 
289 /*****************************************************************************/
291  sensor_msgs::LaserScan::ConstPtr& scan)
292 /*****************************************************************************/
293 {
294  const std::string& frame = scan->header.frame_id;
295  if(lasers_.find(frame) == lasers_.end())
296  {
297  try
298  {
299  lasers_[frame] = laser_assistant_->toLaserMetadata(*scan);
300  dataset_->Add(lasers_[frame].getLaser(), true);
301  }
302  catch (tf2::TransformException& e)
303  {
304  ROS_ERROR("Failed to compute laser pose, aborting initialization (%s)",
305  e.what());
306  return nullptr;
307  }
308  }
309 
310  return lasers_[frame].getLaser();
311 }
312 
313 /*****************************************************************************/
315 /*****************************************************************************/
316 {
317  if (sst_.getNumSubscribers() == 0)
318  {
319  return true;
320  }
321  boost::mutex::scoped_lock lock(smapper_mutex_);
322  karto::OccupancyGrid* occ_grid = smapper_->getOccupancyGrid(resolution_);
323  if(!occ_grid)
324  {
325  return false;
326  }
327 
328  vis_utils::toNavMap(occ_grid, map_.map);
329 
330  // publish map as current
331  map_.map.header.stamp = ros::Time::now();
332  sst_.publish(map_.map);
333  sstm_.publish(map_.map.info);
334 
335  delete occ_grid;
336  occ_grid = nullptr;
337  return true;
338 }
339 
340 /*****************************************************************************/
342  const karto::Pose2& corrected_pose,
343  const karto::Pose2& karto_pose,
344  const ros::Time& t,
345  const bool& update_reprocessing_transform)
346 /*****************************************************************************/
347 {
348  // Compute the map->odom transform
349  tf2::Stamped<tf2::Transform> odom_to_map;
350  tf2::Quaternion q(0.,0.,0.,1.0);
351  q.setRPY(0., 0., corrected_pose.GetHeading());
352  tf2::Stamped<tf2::Transform> base_to_map(
353  tf2::Transform(q, tf2::Vector3(corrected_pose.GetX(),
354  corrected_pose.GetY(), 0.0)).inverse(), t, base_frame_);
355  try
356  {
357  geometry_msgs::TransformStamped base_to_map_msg, odom_to_map_msg;
358  tf2::convert(base_to_map, base_to_map_msg);
359  odom_to_map_msg = tf_->transform(base_to_map_msg, odom_frame_);
360  tf2::convert(odom_to_map_msg, odom_to_map);
361  }
362  catch(tf2::TransformException& e)
363  {
364  ROS_ERROR("Transform from base_link to odom failed: %s", e.what());
365  return odom_to_map;
366  }
367 
368  // if we're continuing a previous session, we need to
369  // estimate the homogenous transformation between the old and new
370  // odometry frames and transform the new session
371  // into the older session's frame
372  if (update_reprocessing_transform)
373  {
374  tf2::Transform odom_to_base_serialized = base_to_map.inverse();
375  tf2::Quaternion q1(0.,0.,0.,1.0);
376  q1.setRPY(0., 0., tf2::getYaw(odom_to_base_serialized.getRotation()));
377  odom_to_base_serialized.setRotation(q1);
378  tf2::Transform odom_to_base_current = smapper_->toTfPose(karto_pose);
380  odom_to_base_serialized * odom_to_base_current.inverse();
381  }
382 
383  // set map to odom for our transformation thread to publish
384  boost::mutex::scoped_lock lock(map_to_odom_mutex_);
385  map_to_odom_ = tf2::Transform(tf2::Quaternion( odom_to_map.getRotation() ),
386  tf2::Vector3( odom_to_map.getOrigin() ) ).inverse();
387 
388  return odom_to_map;
389 }
390 
391 /*****************************************************************************/
394  const sensor_msgs::LaserScan::ConstPtr& scan,
395  karto::Pose2& karto_pose)
396 /*****************************************************************************/
397 {
398  // Create a vector of doubles for karto
399  std::vector<kt_double> readings = laser_utils::scanToReadings(
400  *scan, lasers_[scan->header.frame_id].isInverted());
401 
402  // transform by the reprocessing transform
403  tf2::Transform pose_original = smapper_->toTfPose(karto_pose);
404  tf2::Transform tf_pose_transformed = reprocessing_transform_ * pose_original;
405  karto::Pose2 transformed_pose = smapper_->toKartoPose(tf_pose_transformed);
406 
407  // create localized range scan
409  laser->GetName(), readings);
410  range_scan->SetOdometricPose(transformed_pose);
411  range_scan->SetCorrectedPose(transformed_pose);
412  return range_scan;
413 }
414 
415 /*****************************************************************************/
417  const sensor_msgs::LaserScan::ConstPtr& scan,
418  const karto::Pose2& pose)
419 /*****************************************************************************/
420 {
421  static karto::Pose2 last_pose;
422  static ros::Time last_scan_time = ros::Time(0.);
423  static double min_dist2 =
424  smapper_->getMapper()->getParamMinimumTravelDistance() *
425  smapper_->getMapper()->getParamMinimumTravelDistance();
426 
427  // we give it a pass on the first measurement to get the ball rolling
428  if (first_measurement_)
429  {
430  last_scan_time = scan->header.stamp;
431  last_pose = pose;
432  first_measurement_ = false;
433  return true;
434  }
435 
436  // we are in a paused mode, reject incomming information
438  {
439  return false;
440  }
441 
442  // throttled out
443  if ((scan->header.seq % throttle_scans_) != 0)
444  {
445  return false;
446  }
447 
448  // not enough time
449  if (scan->header.stamp - last_scan_time < minimum_time_interval_)
450  {
451  return false;
452  }
453 
454  // check moved enough, within 10% for correction error
455  const double dist2 = last_pose.SquaredDistance(pose);
456  if(dist2 < 0.8 * min_dist2 || scan->header.seq < 5)
457  {
458  return false;
459  }
460 
461  last_pose = pose;
462  last_scan_time = scan->header.stamp;
463 
464  return true;
465 }
466 
467 /*****************************************************************************/
470  PosedScan& scan_w_pose)
471 /*****************************************************************************/
472 {
473  return addScan(laser, scan_w_pose.scan, scan_w_pose.pose);
474 }
475 
476 /*****************************************************************************/
479  const sensor_msgs::LaserScan::ConstPtr& scan,
480  karto::Pose2& karto_pose)
481 /*****************************************************************************/
482 {
483  // get our localized range scan
485  laser, scan, karto_pose);
486 
487  // Add the localized range scan to the smapper
488  boost::mutex::scoped_lock lock(smapper_mutex_);
489  bool processed = false, update_reprocessing_transform = false;
490 
491  karto::Matrix3 covariance;
492  covariance.SetToIdentity();
493 
494  if (processor_type_ == PROCESS)
495  {
496  processed = smapper_->getMapper()->Process(range_scan, &covariance);
497  }
499  {
500  processed = smapper_->getMapper()->ProcessAtDock(range_scan, &covariance);
502  update_reprocessing_transform = true;
503  }
505  {
506  boost::mutex::scoped_lock l(pose_mutex_);
507  if (!process_near_pose_)
508  {
509  ROS_ERROR("Process near region called without a "
510  "valid region request. Ignoring scan.");
511  return nullptr;
512  }
513  range_scan->SetOdometricPose(*process_near_pose_);
514  range_scan->SetCorrectedPose(range_scan->GetOdometricPose());
515  process_near_pose_.reset(nullptr);
516  processed = smapper_->getMapper()->ProcessAgainstNodesNearBy(range_scan, false, &covariance);
517  update_reprocessing_transform = true;
519  }
520  else
521  {
522  ROS_FATAL("SlamToolbox: No valid processor type set! Exiting.");
523  exit(-1);
524  }
525 
526  // if successfully processed, create odom to map transformation
527  // and add our scan to storage
528  if(processed)
529  {
531  {
532  scan_holder_->addScan(*scan);
533  }
534 
535  setTransformFromPoses(range_scan->GetCorrectedPose(), karto_pose,
536  scan->header.stamp, update_reprocessing_transform);
537  dataset_->Add(range_scan);
538  publishPose(range_scan->GetCorrectedPose(), covariance, scan->header.stamp);
539  }
540  else
541  {
542  delete range_scan;
543  range_scan = nullptr;
544  }
545 
546  return range_scan;
547 }
548 
549 /*****************************************************************************/
551  const karto::Pose2 & pose,
552  const karto::Matrix3 & cov,
553  const ros::Time & t)
554 /*****************************************************************************/
555 {
556  geometry_msgs::PoseWithCovarianceStamped pose_msg;
557  pose_msg.header.stamp = t;
558  pose_msg.header.frame_id = map_frame_;
559 
560  tf2::Quaternion q(0., 0., 0., 1.0);
561  q.setRPY(0., 0., pose.GetHeading());
562  tf2::Transform transform(q, tf2::Vector3(pose.GetX(), pose.GetY(), 0.0));
563  tf2::toMsg(transform, pose_msg.pose.pose);
564 
565  pose_msg.pose.covariance[0] = cov(0, 0) * position_covariance_scale_; // x
566  pose_msg.pose.covariance[1] = cov(0, 1) * position_covariance_scale_; // xy
567  pose_msg.pose.covariance[6] = cov(1, 0) * position_covariance_scale_; // xy
568  pose_msg.pose.covariance[7] = cov(1, 1) * position_covariance_scale_; // y
569  pose_msg.pose.covariance[35] = cov(2, 2) * yaw_covariance_scale_; // yaw
570 
571  pose_pub_.publish(pose_msg);
572 }
573 
574 /*****************************************************************************/
576  nav_msgs::GetMap::Request &req,
577  nav_msgs::GetMap::Response &res)
578 /*****************************************************************************/
579 {
580  if(map_.map.info.width && map_.map.info.height)
581  {
582  boost::mutex::scoped_lock lock(smapper_mutex_);
583  res = map_;
584  return true;
585  }
586  else
587  {
588  return false;
589  }
590 }
591 
592 /*****************************************************************************/
594  slam_toolbox_msgs::Pause::Request& req,
595  slam_toolbox_msgs::Pause::Response& resp)
596 /*****************************************************************************/
597 {
598  bool curr_state = isPaused(NEW_MEASUREMENTS);
599  state_.set(NEW_MEASUREMENTS, !curr_state);
600 
601  nh_.setParam("paused_new_measurements", !curr_state);
602  ROS_INFO("SlamToolbox: Toggled to %s",
603  !curr_state ? "pause taking new measurements." :
604  "actively taking new measurements.");
605  resp.status = true;
606  return true;
607 }
608 
609 /*****************************************************************************/
611 /*****************************************************************************/
612 {
613  return state_.get(app);
614 }
615 
616 /*****************************************************************************/
618  slam_toolbox_msgs::SerializePoseGraph::Request &req,
619  slam_toolbox_msgs::SerializePoseGraph::Response &resp)
620 /*****************************************************************************/
621 {
622  std::string filename = req.filename;
623 
624  // if we're inside the snap, we need to write to commonly accessible space
625  if (snap_utils::isInSnap())
626  {
627  filename = snap_utils::getSnapPath() + std::string("/") + filename;
628  }
629 
630  boost::mutex::scoped_lock lock(smapper_mutex_);
632  return true;
633 }
634 
635 /*****************************************************************************/
637  std::unique_ptr<karto::Mapper>& mapper,
638  std::unique_ptr<karto::Dataset>& dataset)
639 /*****************************************************************************/
640 {
641  boost::mutex::scoped_lock lock(smapper_mutex_);
642 
643  solver_->Reset();
644 
645  // add the nodes and constraints to the optimizer
646  VerticeMap mapper_vertices = mapper->GetGraph()->GetVertices();
647  VerticeMap::iterator vertex_map_it = mapper_vertices.begin();
648  for(vertex_map_it; vertex_map_it != mapper_vertices.end(); ++vertex_map_it)
649  {
650  ScanMap::iterator vertex_it = vertex_map_it->second.begin();
651  for(vertex_it; vertex_it != vertex_map_it->second.end(); ++vertex_it)
652  {
653  if (vertex_it->second != nullptr)
654  {
655  solver_->AddNode(vertex_it->second);
656  }
657  }
658  }
659 
660  EdgeVector mapper_edges = mapper->GetGraph()->GetEdges();
661  EdgeVector::iterator edges_it = mapper_edges.begin();
662  for( edges_it; edges_it != mapper_edges.end(); ++edges_it)
663  {
664  if (*edges_it != nullptr)
665  {
666  solver_->AddConstraint(*edges_it);
667  }
668  }
669 
670  mapper->SetScanSolver(solver_.get());
671 
672  // move the memory to our working dataset
673  smapper_->setMapper(mapper.release());
674  smapper_->configure(nh_);
675  dataset_.reset(dataset.release());
676 
677  closure_assistant_->setMapper(smapper_->getMapper());
678 
679  if (!smapper_->getMapper())
680  {
681  ROS_FATAL("loadSerializedPoseGraph: Could not properly load "
682  "a valid mapping object. Did you modify something by hand?");
683  exit(-1);
684  }
685 
686  if (dataset_->GetLasers().size() < 1)
687  {
688  ROS_FATAL("loadSerializedPoseGraph: Cannot deserialize "
689  "dataset with no laser objects.");
690  exit(-1);
691  }
692 
693  // create a current laser sensor
694  karto::LaserRangeFinder* laser =
695  dynamic_cast<karto::LaserRangeFinder*>(
696  dataset_->GetLasers()[0]);
697  karto::Sensor* pSensor = dynamic_cast<karto::Sensor*>(laser);
698  if (pSensor)
699  {
701 
702  while (ros::ok())
703  {
704  ROS_INFO("Waiting for incoming scan to get metadata...");
706  ros::topic::waitForMessage<sensor_msgs::LaserScan>(
707  scan_topic_, ros::Duration(1.0));
708  if (scan)
709  {
710  ROS_INFO("Got scan!");
711  try
712  {
713  lasers_[scan->header.frame_id] =
714  laser_assistant_->toLaserMetadata(*scan);
715  break;
716  }
717  catch (tf2::TransformException& e)
718  {
719  ROS_ERROR("Failed to compute laser pose, aborting continue mapping (%s)",
720  e.what());
721  exit(-1);
722  }
723  }
724  }
725  }
726  else
727  {
728  ROS_ERROR("Invalid sensor pointer in dataset. Unable to register sensor.");
729  }
730 
731  solver_->Compute();
732 
733  return;
734 }
735 
736 /*****************************************************************************/
738  slam_toolbox_msgs::DeserializePoseGraph::Request &req,
739  slam_toolbox_msgs::DeserializePoseGraph::Response &resp)
740 /*****************************************************************************/
741 {
742  if (req.match_type == slam_toolbox_msgs::DeserializePoseGraph::Request::UNSET)
743  {
744  ROS_ERROR("Deserialization called without valid processor type set. "
745  "Undefined behavior!");
746  return false;
747  }
748 
749  std::string filename = req.filename;
750 
751  if (filename.empty())
752  {
753  ROS_WARN("No map file given!");
754  return true;
755  }
756 
757  // if we're inside the snap, we need to write to commonly accessible space
758  if (snap_utils::isInSnap())
759  {
760  filename = snap_utils::getSnapPath() + std::string("/") + filename;
761  }
762 
763  std::unique_ptr<karto::Dataset> dataset = std::make_unique<karto::Dataset>();
764  std::unique_ptr<karto::Mapper> mapper = std::make_unique<karto::Mapper>();
765 
766  if (!serialization::read(filename, *mapper, *dataset))
767  {
768  ROS_ERROR("DeserializePoseGraph: Failed to read "
769  "file: %s.", filename.c_str());
770  return true;
771  }
772  ROS_DEBUG("DeserializePoseGraph: Successfully read file.");
773 
774  loadSerializedPoseGraph(mapper, dataset);
775  updateMap();
776 
777  first_measurement_ = true;
778  boost::mutex::scoped_lock l(pose_mutex_);
779  switch (req.match_type)
780  {
781  case procType::START_AT_FIRST_NODE:
783  break;
784  case procType::START_AT_GIVEN_POSE:
786  process_near_pose_ = std::make_unique<karto::Pose2>(req.initial_pose.x,
787  req.initial_pose.y, req.initial_pose.theta);
788  break;
789  case procType::LOCALIZE_AT_POSE:
791  process_near_pose_ = std::make_unique<karto::Pose2>(req.initial_pose.x,
792  req.initial_pose.y, req.initial_pose.theta);
793  break;
794  default:
795  ROS_FATAL("Deserialization called without valid processor type set.");
796  }
797 
798  return true;
799 }
800 
801 /*****************************************************************************/
803  slam_toolbox_msgs::Reset::Request &req,
804  slam_toolbox_msgs::Reset::Response &resp)
805 /*****************************************************************************/
806 {
807  boost::mutex::scoped_lock lock(smapper_mutex_);
808  // Reset the map.
809  smapper_->Reset();
810  smapper_->getMapper()->getScanSolver()->Reset();
811 
812  // Ensure we will process the next available scan.
813  first_measurement_ = true;
814 
815  // Pause new measurements processing if requested.
816  if (req.pause_new_measurements) {
817  state_.set(NEW_MEASUREMENTS, true);
818  nh_.setParam("paused_new_measurements", true);
819  ROS_INFO("SlamToolbox: Toggled to pause taking new measurements after reset.");
820  }
821 
822  resp.result = true;
823  return true;
824 }
825 
826 } // end namespace
slam_toolbox::SlamToolbox::process_near_pose_
std::unique_ptr< karto::Pose2 > process_near_pose_
Definition: slam_toolbox_common.hpp:143
karto::Pose2::SquaredDistance
kt_double SquaredDistance(const Pose2 &rOther) const
Definition: Karto.h:2171
slam_toolbox::SlamToolbox::scan_holder_
std::unique_ptr< laser_utils::ScanHolder > scan_holder_
Definition: slam_toolbox_common.hpp:134
slam_toolbox::SlamToolbox::map_
nav_msgs::GetMap::Response map_
Definition: slam_toolbox_common.hpp:141
tf2::convert
void convert(const A &a, B &b)
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
slam_toolbox::SlamToolbox::ssSerialize_
ros::ServiceServer ssSerialize_
Definition: slam_toolbox_common.hpp:112
karto::SensorManager::RegisterSensor
void RegisterSensor(Sensor *pSensor, kt_bool override=false)
Definition: Karto.h:3732
toolbox_types::PROCESS
@ PROCESS
Definition: toolbox_types.hpp:86
toolbox_types::PausedApplication
PausedApplication
Definition: toolbox_types.hpp:76
slam_toolbox::SlamToolbox::ssMap_
ros::ServiceServer ssMap_
Definition: slam_toolbox_common.hpp:112
slam_toolbox::SlamToolbox::threads_
std::vector< std::unique_ptr< boost::thread > > threads_
Definition: slam_toolbox_common.hpp:137
slam_toolbox::SlamToolbox::scan_filter_
std::unique_ptr< tf2_ros::MessageFilter< sensor_msgs::LaserScan > > scan_filter_
Definition: slam_toolbox_common.hpp:110
slam_toolbox::SlamToolbox::solver_loader_
pluginlib::ClassLoader< karto::ScanSolver > solver_loader_
Definition: slam_toolbox_common.hpp:147
slam_toolbox::SlamToolbox::nh_
ros::NodeHandle nh_
Definition: slam_toolbox_common.hpp:105
slam_toolbox::SlamToolbox::getLaser
karto::LaserRangeFinder * getLaser(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: slam_toolbox_common.cpp:290
karto::Object::GetName
const Name & GetName() const
Definition: Karto.h:658
slam_toolbox::SlamToolbox::publishPose
void publishPose(const karto::Pose2 &pose, const karto::Matrix3 &cov, const ros::Time &t)
Definition: slam_toolbox_common.cpp:550
karto::LocalizedRangeScan::GetOdometricPose
const Pose2 & GetOdometricPose() const
Definition: Karto.h:5540
karto::LaserRangeFinder
Definition: Karto.h:3922
boost::shared_ptr
slam_toolbox::SlamToolbox::yaw_covariance_scale_
double yaw_covariance_scale_
Definition: slam_toolbox_common.hpp:121
tf2::Transform::inverse
Transform inverse() const
slam_toolbox::SlamToolbox::getLocalizedRangeScan
karto::LocalizedRangeScan * getLocalizedRangeScan(karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
Definition: slam_toolbox_common.cpp:392
tf2::getYaw
double getYaw(const A &a)
karto::OccupancyGrid
Definition: Karto.h:6008
slam_toolbox::SlamToolbox::setSolver
void setSolver(ros::NodeHandle &private_nh_)
Definition: slam_toolbox_common.cpp:83
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
slam_toolbox::SlamToolbox::updateMap
bool updateMap()
Definition: slam_toolbox_common.cpp:314
laser_utils::scanToReadings
std::vector< double > scanToReadings(const sensor_msgs::LaserScan &scan, const bool &inverted)
Definition: laser_utils.hpp:33
slam_toolbox::SlamToolbox::state_
PausedState state_
Definition: slam_toolbox_common.hpp:140
karto::Pose2::GetY
kt_double GetY() const
Definition: Karto.h:2117
slam_toolbox_common.hpp
slam_toolbox::SlamToolbox::laser_assistant_
std::unique_ptr< laser_utils::LaserAssistant > laser_assistant_
Definition: slam_toolbox_common.hpp:130
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
tf2::Transform::setRotation
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
toolbox_types::PROCESS_NEAR_REGION
@ PROCESS_NEAR_REGION
Definition: toolbox_types.hpp:88
slam_toolbox::SlamToolbox::transform_timeout_
ros::Duration transform_timeout_
Definition: slam_toolbox_common.hpp:116
slam_toolbox::SlamToolbox::shouldProcessScan
bool shouldProcessScan(const sensor_msgs::LaserScan::ConstPtr &scan, const karto::Pose2 &pose)
Definition: slam_toolbox_common.cpp:416
slam_toolbox::SlamToolbox::resetCallback
virtual bool resetCallback(slam_toolbox_msgs::Reset::Request &req, slam_toolbox_msgs::Reset::Response &resp)
Definition: slam_toolbox_common.cpp:802
karto::LocalizedRangeScan::SetOdometricPose
void SetOdometricPose(const Pose2 &rPose)
Definition: Karto.h:5549
slam_toolbox::SlamToolbox::smapper_
std::unique_ptr< mapper_utils::SMapper > smapper_
Definition: slam_toolbox_common.hpp:125
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
serialization::read
bool read(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
Definition: serialization.hpp:53
vis_utils::toNavMap
void toNavMap(const karto::OccupancyGrid *occ_grid, nav_msgs::OccupancyGrid &map)
Definition: visualization_utils.hpp:122
slam_toolbox::SlamToolbox::deserializePoseGraphCallback
virtual bool deserializePoseGraphCallback(slam_toolbox_msgs::DeserializePoseGraph::Request &req, slam_toolbox_msgs::DeserializePoseGraph::Response &resp)
Definition: slam_toolbox_common.cpp:737
tf2::Stamped
karto::LocalizedRangeScan
Definition: Karto.h:5505
slam_toolbox::SlamToolbox::closure_assistant_
std::unique_ptr< loop_closure_assistant::LoopClosureAssistant > closure_assistant_
Definition: slam_toolbox_common.hpp:133
slam_toolbox::SlamToolbox::map_saver_
std::unique_ptr< map_saver::MapSaver > map_saver_
Definition: slam_toolbox_common.hpp:132
slam_toolbox::SlamToolbox::setTransformFromPoses
tf2::Stamped< tf2::Transform > setTransformFromPoses(const karto::Pose2 &pose, const karto::Pose2 &karto_pose, const ros::Time &t, const bool &update_reprocessing_transform)
Definition: slam_toolbox_common.cpp:341
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
slam_toolbox::SlamToolbox::isPaused
bool isPaused(const PausedApplication &app)
Definition: slam_toolbox_common.cpp:610
slam_toolbox::SlamToolbox::SlamToolbox
SlamToolbox(ros::NodeHandle &nh)
Definition: slam_toolbox_common.cpp:28
slam_toolbox::SlamToolbox::tfB_
std::unique_ptr< tf2_ros::TransformBroadcaster > tfB_
Definition: slam_toolbox_common.hpp:108
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
slam_toolbox::SlamToolbox::reprocessing_transform_
tf2::Transform reprocessing_transform_
Definition: slam_toolbox_common.hpp:144
karto::Matrix3::SetToIdentity
void SetToIdentity()
Definition: Karto.h:2467
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
serialization.hpp
karto::Matrix3
Definition: Karto.h:2444
slam_toolbox::SlamToolbox::throttle_scans_
int throttle_scans_
Definition: slam_toolbox_common.hpp:117
pluginlib::PluginlibException
slam_toolbox::SlamToolbox::publishVisualizations
void publishVisualizations()
Definition: slam_toolbox_common.cpp:192
toolbox_types::PROCESS_FIRST_NODE
@ PROCESS_FIRST_NODE
Definition: toolbox_types.hpp:87
slam_toolbox::SlamToolbox::enable_interactive_mode_
bool enable_interactive_mode_
Definition: slam_toolbox_common.hpp:122
ros::console::levels::Debug
Debug
toolbox_types::NEW_MEASUREMENTS
@ NEW_MEASUREMENTS
Definition: toolbox_types.hpp:80
slam_toolbox::SlamToolbox::sst_
ros::Publisher sst_
Definition: slam_toolbox_common.hpp:111
slam_toolbox::SlamToolbox::~SlamToolbox
~SlamToolbox()
Definition: slam_toolbox_common.cpp:65
ROS_DEBUG
#define ROS_DEBUG(...)
karto::SensorManager::GetInstance
static SensorManager * GetInstance()
Definition: Karto.cpp:57
slam_toolbox::SlamToolbox::serializePoseGraphCallback
virtual bool serializePoseGraphCallback(slam_toolbox_msgs::SerializePoseGraph::Request &req, slam_toolbox_msgs::SerializePoseGraph::Response &resp)
Definition: slam_toolbox_common.cpp:617
slam_toolbox::SlamToolbox::tf_buffer_dur_
ros::Duration tf_buffer_dur_
Definition: slam_toolbox_common.hpp:116
slam_toolbox::SlamToolbox::ssReset_
ros::ServiceServer ssReset_
Definition: slam_toolbox_common.hpp:112
slam_toolbox::SlamToolbox::resolution_
double resolution_
Definition: slam_toolbox_common.hpp:119
slam_toolbox::SlamToolbox::tf_
std::unique_ptr< tf2_ros::Buffer > tf_
Definition: slam_toolbox_common.hpp:106
slam_toolbox::SlamToolbox::smapper_mutex_
boost::mutex smapper_mutex_
Definition: slam_toolbox_common.hpp:139
slam_toolbox::SlamToolbox::setROSInterfaces
void setROSInterfaces(ros::NodeHandle &node)
Definition: slam_toolbox_common.cpp:147
slam_toolbox::SlamToolbox::solver_
boost::shared_ptr< karto::ScanSolver > solver_
Definition: slam_toolbox_common.hpp:148
tf2::Transform
tf2::Transform::getRotation
Quaternion getRotation() const
slam_toolbox::SlamToolbox::map_to_odom_
tf2::Transform map_to_odom_
Definition: slam_toolbox_common.hpp:138
slam_toolbox::SlamToolbox::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: slam_toolbox_common.cpp:575
slam_toolbox::SlamToolbox::lasers_
std::map< std::string, laser_utils::LaserMetadata > lasers_
Definition: slam_toolbox_common.hpp:127
slam_toolbox::SlamToolbox::map_frame_
std::string map_frame_
Definition: slam_toolbox_common.hpp:115
karto::LocalizedRangeScan::SetCorrectedPose
void SetCorrectedPose(const Pose2 &rPose)
Definition: Karto.h:5571
slam_toolbox::SlamToolbox::position_covariance_scale_
double position_covariance_scale_
Definition: slam_toolbox_common.hpp:120
ROS_WARN
#define ROS_WARN(...)
karto::LocalizedRangeScan::GetCorrectedPose
const Pose2 & GetCorrectedPose() const
Definition: Karto.h:5562
slam_toolbox::SlamToolbox::setParams
void setParams(ros::NodeHandle &nh)
Definition: slam_toolbox_common.cpp:108
slam_toolbox::SlamToolbox::ssDesserialize_
ros::ServiceServer ssDesserialize_
Definition: slam_toolbox_common.hpp:112
slam_toolbox::SlamToolbox::loadSerializedPoseGraph
void loadSerializedPoseGraph(std::unique_ptr< karto::Mapper > &, std::unique_ptr< karto::Dataset > &)
Definition: slam_toolbox_common.cpp:636
app
app
ros::Rate::sleep
bool sleep()
ROS_FATAL
#define ROS_FATAL(...)
slam_toolbox::SlamToolbox::scan_topic_
std::string scan_topic_
Definition: slam_toolbox_common.hpp:115
toolbox_types::VerticeMap
std::map< karto::Name, std::map< int, karto::Vertex< karto::LocalizedRangeScan > * > > VerticeMap
Definition: toolbox_types.hpp:118
slam_toolbox::SlamToolbox::loadPoseGraphByParams
void loadPoseGraphByParams(ros::NodeHandle &nh)
Definition: slam_toolbox_common.cpp:224
slam_toolbox::SlamToolbox::shouldStartWithPoseGraph
bool shouldStartWithPoseGraph(std::string &filename, geometry_msgs::Pose2D &pose, bool &start_at_dock)
Definition: slam_toolbox_common.cpp:251
slam_toolbox::SlamToolbox::first_measurement_
bool first_measurement_
Definition: slam_toolbox_common.hpp:122
slam_toolbox::SlamToolbox::processor_type_
ProcessType processor_type_
Definition: slam_toolbox_common.hpp:142
slam_toolbox::SlamToolbox::base_frame_
std::string base_frame_
Definition: slam_toolbox_common.hpp:115
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
pluginlib::ClassLoader::createInstance
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
ros::Time
slam_toolbox::SlamToolbox::addScan
virtual karto::LocalizedRangeScan * addScan(karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
Definition: slam_toolbox_common.cpp:477
slam_toolbox::SlamToolbox::dataset_
std::unique_ptr< karto::Dataset > dataset_
Definition: slam_toolbox_common.hpp:126
slam_toolbox::SlamToolbox::scan_filter_sub_
std::unique_ptr< message_filters::Subscriber< sensor_msgs::LaserScan > > scan_filter_sub_
Definition: slam_toolbox_common.hpp:109
slam_toolbox::SlamToolbox::minimum_time_interval_
ros::Duration minimum_time_interval_
Definition: slam_toolbox_common.hpp:116
karto::Pose2::GetX
kt_double GetX() const
Definition: Karto.h:2099
ROS_ERROR
#define ROS_ERROR(...)
slam_toolbox::SlamToolbox::tfL_
std::unique_ptr< tf2_ros::TransformListener > tfL_
Definition: slam_toolbox_common.hpp:107
slam_toolbox::SlamToolbox::pose_helper_
std::unique_ptr< pose_utils::GetPoseHelper > pose_helper_
Definition: slam_toolbox_common.hpp:131
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
slam_toolbox::SlamToolbox::map_name_
std::string map_name_
Definition: slam_toolbox_common.hpp:115
tf2::toMsg
B toMsg(const A &a)
snap_utils::getSnapPath
std::string getSnapPath()
Definition: snap_utils.hpp:37
slam_toolbox::SlamToolbox::sstm_
ros::Publisher sstm_
Definition: slam_toolbox_common.hpp:111
ros::Rate
slam_toolbox
Definition: slam_toolbox_lifelong.hpp:24
process_constraints.filename
filename
Definition: process_constraints.py:114
inverse
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
karto::Pose2
Definition: Karto.h:2046
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
slam_toolbox::SlamToolbox::pauseNewMeasurementsCallback
bool pauseNewMeasurementsCallback(slam_toolbox_msgs::Pause::Request &req, slam_toolbox_msgs::Pause::Response &resp)
Definition: slam_toolbox_common.cpp:593
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
toolbox_types::VISUALIZING_GRAPH
@ VISUALIZING_GRAPH
Definition: toolbox_types.hpp:79
header
const std::string header
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
slam_toolbox::SlamToolbox::map_to_odom_mutex_
boost::mutex map_to_odom_mutex_
Definition: slam_toolbox_common.hpp:139
toolbox_types::PROCESS_LOCALIZATION
@ PROCESS_LOCALIZATION
Definition: toolbox_types.hpp:89
slam_toolbox::SlamToolbox::publishTransformLoop
void publishTransformLoop(const double &transform_publish_period)
Definition: slam_toolbox_common.cpp:167
toolbox_types::EdgeVector
std::vector< karto::Edge< karto::LocalizedRangeScan > * > EdgeVector
Definition: toolbox_types.hpp:119
karto::Sensor
Definition: Karto.h:3600
ros::Duration
slam_toolbox::SlamToolbox::odom_frame_
std::string odom_frame_
Definition: slam_toolbox_common.hpp:115
t
geometry_msgs::TransformStamped t
serialization::write
void write(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
Definition: serialization.hpp:38
karto::Pose2::GetHeading
kt_double GetHeading() const
Definition: Karto.h:2153
slam_toolbox::SlamToolbox::pose_mutex_
boost::mutex pose_mutex_
Definition: slam_toolbox_common.hpp:139
ros::NodeHandle
slam_toolbox::SlamToolbox::pose_pub_
ros::Publisher pose_pub_
Definition: slam_toolbox_common.hpp:111
slam_toolbox::SlamToolbox::ssPauseMeasurements_
ros::ServiceServer ssPauseMeasurements_
Definition: slam_toolbox_common.hpp:112
slam_toolbox::SlamToolbox::laserCallback
virtual void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)=0
ros::Time::now
static Time now()
tf2::Transform::setIdentity
void setIdentity()
snap_utils::isInSnap
bool isInSnap()
Definition: snap_utils.hpp:26


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 23 2025 03:37:19