33 "clear_localization_buffer",
37 geometry_msgs::Pose2D pose;
41 slam_toolbox_msgs::DeserializePoseGraph::Request req;
42 slam_toolbox_msgs::DeserializePoseGraph::Response resp;
43 req.initial_pose = pose;
46 slam_toolbox_msgs::DeserializePoseGraph::Request::LOCALIZE_AT_POSE;
49 ROS_ERROR(
"LocalizationSlamToolbox: Starting localization "
50 "at first node (dock) is correctly not supported.");
66 std_srvs::Empty::Request& req,
67 std_srvs::Empty::Response& resp)
71 ROS_INFO(
"LocalizationSlamToolbox: Clearing localization buffer.");
78 slam_toolbox_msgs::SerializePoseGraph::Request& req,
79 slam_toolbox_msgs::SerializePoseGraph::Response& resp)
82 ROS_FATAL(
"LocalizationSlamToolbox: Cannot call serialize map "
83 "in localization mode!");
89 slam_toolbox_msgs::DeserializePoseGraph::Request& req,
90 slam_toolbox_msgs::DeserializePoseGraph::Response& resp)
93 if (req.match_type != procType::LOCALIZE_AT_POSE)
95 ROS_ERROR(
"Requested a non-localization deserialization "
96 "in localization mode.");
104 const sensor_msgs::LaserScan::ConstPtr& scan)
109 if(!
pose_helper_->getOdomPose(pose, scan->header.stamp))
115 LaserRangeFinder* laser =
getLaser(scan);
120 " device for %s; discarding scan", scan->header.frame_id.c_str());
134 LaserRangeFinder* laser,
135 const sensor_msgs::LaserScan::ConstPtr& scan,
147 laser, scan, karto_pose);
151 bool processed =
false, update_reprocessing_transform =
false;
156 ROS_ERROR(
"Process near region called without a "
157 "valid region request. Ignoring scan.");
163 range_scan->SetCorrectedPose(range_scan->GetOdometricPose());
165 processed =
smapper_->getMapper()->ProcessAgainstNodesNearBy(range_scan,
true);
169 update_reprocessing_transform =
true;
173 processed =
smapper_->getMapper()->ProcessLocalization(range_scan);
174 update_reprocessing_transform =
false;
179 "No valid processor type set! Exiting.");
187 range_scan =
nullptr;
191 scan->header.stamp, update_reprocessing_transform);
199 geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
204 ROS_ERROR(
"LocalizePoseCallback: Cannot process localization command "
205 "if not in localization mode.");
213 msg->pose.pose.position.y,
tf2::getYaw(msg->pose.pose.orientation)));
218 msg->pose.pose.position.y,
tf2::getYaw(msg->pose.pose.orientation));
224 smapper_->clearLocalizationBuffer();
226 ROS_INFO(
"LocalizePoseCallback: Localizing to: (%0.2f %0.2f), theta=%0.2f",
227 msg->pose.pose.position.x, msg->pose.pose.position.y,