29 : solver_loader_(
"slam_toolbox",
"karto::ScanSolver"),
31 first_measurement_(true),
33 process_near_pose_(nullptr)
36 smapper_ = std::make_unique<mapper_utils::SMapper>();
37 dataset_ = std::make_unique<karto::Dataset>();
45 pose_helper_ = std::make_unique<pose_utils::GetPoseHelper>(
50 std::make_unique<loop_closure_assistant::LoopClosureAssistant>(
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>(
68 for (
int i=0; i !=
threads_.size(); i++)
87 std::string solver_plugin;
88 if(!private_nh_.
getParam(
"solver_plugin", solver_plugin))
90 ROS_WARN(
"unable to find requested solver plugin, defaulting to SPA");
91 solver_plugin =
"solver_plugins::CeresSolver";
96 ROS_INFO(
"Using plugin %s", solver_plugin.c_str());
100 ROS_FATAL(
"Failed to create %s, is it registered and built? Exception: %s.",
101 solver_plugin.c_str(), ex.what());
122 private_nh.
param(
"transform_timeout", tmp_val, 0.2);
124 private_nh.
param(
"tf_buffer_duration", tmp_val, 30.);
126 private_nh.
param(
"minimum_time_interval", tmp_val, 0.5);
133 if (private_nh.
getParam(
"debug_logging", debug) && debug)
143 private_nh.
setParam(
"paused_new_measurements",
false);
151 tfL_ = std::make_unique<tf2_ros::TransformListener>(*
tf_);
152 tfB_ = std::make_unique<tf2_ros::TransformBroadcaster>();
163 pose_pub_ = node.advertise<geometry_msgs::PoseWithCovarianceStamped>(
"pose", 10,
true);
170 if(transform_publish_period == 0)
175 ros::Rate r(1.0 / transform_publish_period);
180 geometry_msgs::TransformStamped msg;
185 tfB_->sendTransform(msg);
195 nav_msgs::OccupancyGrid& og =
map_.map;
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;
206 double map_update_interval;
207 if(!
nh_.
getParam(
"map_update_interval", map_update_interval))
208 map_update_interval = 10.0;
228 geometry_msgs::Pose2D pose;
232 slam_toolbox_msgs::DeserializePoseGraph::Request req;
233 slam_toolbox_msgs::DeserializePoseGraph::Response resp;
234 req.initial_pose = pose;
239 slam_toolbox_msgs::DeserializePoseGraph::Request::START_AT_FIRST_NODE;
244 slam_toolbox_msgs::DeserializePoseGraph::Request::START_AT_GIVEN_POSE;
252 geometry_msgs::Pose2D& pose,
bool& start_at_dock)
258 std::vector<double> read_pose;
261 start_at_dock =
false;
262 if (read_pose.size() != 3)
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");
273 pose.x = read_pose[0];
274 pose.y = read_pose[1];
275 pose.theta = read_pose[2];
291 sensor_msgs::LaserScan::ConstPtr& scan)
294 const std::string& frame = scan->header.frame_id;
304 ROS_ERROR(
"Failed to compute laser pose, aborting initialization (%s)",
310 return lasers_[frame].getLaser();
345 const bool& update_reprocessing_transform)
357 geometry_msgs::TransformStamped base_to_map_msg, odom_to_map_msg;
364 ROS_ERROR(
"Transform from base_link to odom failed: %s", e.what());
372 if (update_reprocessing_transform)
380 odom_to_base_serialized * odom_to_base_current.
inverse();
386 tf2::Vector3( odom_to_map.getOrigin() ) ).
inverse();
394 const sensor_msgs::LaserScan::ConstPtr& scan,
400 *scan,
lasers_[scan->header.frame_id].isInverted());
417 const sensor_msgs::LaserScan::ConstPtr& scan,
423 static double min_dist2 =
424 smapper_->getMapper()->getParamMinimumTravelDistance() *
425 smapper_->getMapper()->getParamMinimumTravelDistance();
430 last_scan_time = scan->header.stamp;
456 if(dist2 < 0.8 * min_dist2 || scan->
header.seq < 5)
462 last_scan_time = scan->header.stamp;
470 PosedScan& scan_w_pose)
473 return addScan(laser, scan_w_pose.scan, scan_w_pose.pose);
479 const sensor_msgs::LaserScan::ConstPtr& scan,
485 laser, scan, karto_pose);
489 bool processed =
false, update_reprocessing_transform =
false;
496 processed =
smapper_->getMapper()->Process(range_scan, &covariance);
500 processed =
smapper_->getMapper()->ProcessAtDock(range_scan, &covariance);
502 update_reprocessing_transform =
true;
509 ROS_ERROR(
"Process near region called without a "
510 "valid region request. Ignoring scan.");
516 processed =
smapper_->getMapper()->ProcessAgainstNodesNearBy(range_scan,
false, &covariance);
517 update_reprocessing_transform =
true;
522 ROS_FATAL(
"SlamToolbox: No valid processor type set! Exiting.");
536 scan->header.stamp, update_reprocessing_transform);
543 range_scan =
nullptr;
556 geometry_msgs::PoseWithCovarianceStamped pose_msg;
557 pose_msg.header.stamp =
t;
576 nav_msgs::GetMap::Request &req,
577 nav_msgs::GetMap::Response &res)
580 if(
map_.map.info.width &&
map_.map.info.height)
594 slam_toolbox_msgs::Pause::Request& req,
595 slam_toolbox_msgs::Pause::Response& resp)
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.");
618 slam_toolbox_msgs::SerializePoseGraph::Request &req,
619 slam_toolbox_msgs::SerializePoseGraph::Response &resp)
622 std::string
filename = req.filename;
637 std::unique_ptr<karto::Mapper>& mapper,
638 std::unique_ptr<karto::Dataset>& dataset)
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)
650 ScanMap::iterator vertex_it = vertex_map_it->second.begin();
651 for(vertex_it; vertex_it != vertex_map_it->second.end(); ++vertex_it)
653 if (vertex_it->second !=
nullptr)
655 solver_->AddNode(vertex_it->second);
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)
664 if (*edges_it !=
nullptr)
666 solver_->AddConstraint(*edges_it);
670 mapper->SetScanSolver(
solver_.get());
673 smapper_->setMapper(mapper.release());
681 ROS_FATAL(
"loadSerializedPoseGraph: Could not properly load "
682 "a valid mapping object. Did you modify something by hand?");
686 if (
dataset_->GetLasers().size() < 1)
688 ROS_FATAL(
"loadSerializedPoseGraph: Cannot deserialize "
689 "dataset with no laser objects.");
704 ROS_INFO(
"Waiting for incoming scan to get metadata...");
706 ros::topic::waitForMessage<sensor_msgs::LaserScan>(
713 lasers_[scan->header.frame_id] =
719 ROS_ERROR(
"Failed to compute laser pose, aborting continue mapping (%s)",
728 ROS_ERROR(
"Invalid sensor pointer in dataset. Unable to register sensor.");
738 slam_toolbox_msgs::DeserializePoseGraph::Request &req,
739 slam_toolbox_msgs::DeserializePoseGraph::Response &resp)
742 if (req.match_type == slam_toolbox_msgs::DeserializePoseGraph::Request::UNSET)
744 ROS_ERROR(
"Deserialization called without valid processor type set. "
745 "Undefined behavior!");
749 std::string
filename = req.filename;
763 std::unique_ptr<karto::Dataset> dataset = std::make_unique<karto::Dataset>();
764 std::unique_ptr<karto::Mapper> mapper = std::make_unique<karto::Mapper>();
768 ROS_ERROR(
"DeserializePoseGraph: Failed to read "
772 ROS_DEBUG(
"DeserializePoseGraph: Successfully read file.");
779 switch (req.match_type)
781 case procType::START_AT_FIRST_NODE:
784 case procType::START_AT_GIVEN_POSE:
787 req.initial_pose.y, req.initial_pose.theta);
789 case procType::LOCALIZE_AT_POSE:
792 req.initial_pose.y, req.initial_pose.theta);
795 ROS_FATAL(
"Deserialization called without valid processor type set.");
803 slam_toolbox_msgs::Reset::Request &req,
804 slam_toolbox_msgs::Reset::Response &resp)
810 smapper_->getMapper()->getScanSolver()->Reset();
816 if (req.pause_new_measurements) {
819 ROS_INFO(
"SlamToolbox: Toggled to pause taking new measurements after reset.");