00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer_ros/node.h"
00018
00019 #include <chrono>
00020 #include <string>
00021 #include <vector>
00022
00023 #include "Eigen/Core"
00024 #include "absl/memory/memory.h"
00025 #include "absl/strings/str_cat.h"
00026 #include "cartographer/common/configuration_file_resolver.h"
00027 #include "cartographer/common/lua_parameter_dictionary.h"
00028 #include "cartographer/common/port.h"
00029 #include "cartographer/common/time.h"
00030 #include "cartographer/mapping/pose_graph_interface.h"
00031 #include "cartographer/mapping/proto/submap_visualization.pb.h"
00032 #include "cartographer/metrics/register.h"
00033 #include "cartographer/sensor/point_cloud.h"
00034 #include "cartographer/transform/rigid_transform.h"
00035 #include "cartographer/transform/transform.h"
00036 #include "cartographer_ros/metrics/family_factory.h"
00037 #include "cartographer_ros/msg_conversion.h"
00038 #include "cartographer_ros/sensor_bridge.h"
00039 #include "cartographer_ros/tf_bridge.h"
00040 #include "cartographer_ros/time_conversion.h"
00041 #include "cartographer_ros_msgs/StatusCode.h"
00042 #include "cartographer_ros_msgs/StatusResponse.h"
00043 #include "glog/logging.h"
00044 #include "nav_msgs/Odometry.h"
00045 #include "ros/serialization.h"
00046 #include "sensor_msgs/PointCloud2.h"
00047 #include "tf2_eigen/tf2_eigen.h"
00048 #include "visualization_msgs/MarkerArray.h"
00049
00050 namespace cartographer_ros {
00051
00052 namespace carto = ::cartographer;
00053
00054 using carto::transform::Rigid3d;
00055 using TrajectoryState =
00056 ::cartographer::mapping::PoseGraphInterface::TrajectoryState;
00057
00058 namespace {
00059
00060
00061 template <typename MessageType>
00062 ::ros::Subscriber SubscribeWithHandler(
00063 void (Node::*handler)(int, const std::string&,
00064 const typename MessageType::ConstPtr&),
00065 const int trajectory_id, const std::string& topic,
00066 ::ros::NodeHandle* const node_handle, Node* const node) {
00067 return node_handle->subscribe<MessageType>(
00068 topic, kInfiniteSubscriberQueueSize,
00069 boost::function<void(const typename MessageType::ConstPtr&)>(
00070 [node, handler, trajectory_id,
00071 topic](const typename MessageType::ConstPtr& msg) {
00072 (node->*handler)(trajectory_id, topic, msg);
00073 }));
00074 }
00075
00076 std::string TrajectoryStateToString(const TrajectoryState trajectory_state) {
00077 switch (trajectory_state) {
00078 case TrajectoryState::ACTIVE:
00079 return "ACTIVE";
00080 case TrajectoryState::FINISHED:
00081 return "FINISHED";
00082 case TrajectoryState::FROZEN:
00083 return "FROZEN";
00084 case TrajectoryState::DELETED:
00085 return "DELETED";
00086 }
00087 return "";
00088 }
00089
00090 }
00091
00092 Node::Node(
00093 const NodeOptions& node_options,
00094 std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
00095 tf2_ros::Buffer* const tf_buffer, const bool collect_metrics)
00096 : node_options_(node_options),
00097 map_builder_bridge_(node_options_, std::move(map_builder), tf_buffer) {
00098 absl::MutexLock lock(&mutex_);
00099 if (collect_metrics) {
00100 metrics_registry_ = absl::make_unique<metrics::FamilyFactory>();
00101 carto::metrics::RegisterAllMetrics(metrics_registry_.get());
00102 }
00103
00104 submap_list_publisher_ =
00105 node_handle_.advertise<::cartographer_ros_msgs::SubmapList>(
00106 kSubmapListTopic, kLatestOnlyPublisherQueueSize);
00107 trajectory_node_list_publisher_ =
00108 node_handle_.advertise<::visualization_msgs::MarkerArray>(
00109 kTrajectoryNodeListTopic, kLatestOnlyPublisherQueueSize);
00110 landmark_poses_list_publisher_ =
00111 node_handle_.advertise<::visualization_msgs::MarkerArray>(
00112 kLandmarkPosesListTopic, kLatestOnlyPublisherQueueSize);
00113 constraint_list_publisher_ =
00114 node_handle_.advertise<::visualization_msgs::MarkerArray>(
00115 kConstraintListTopic, kLatestOnlyPublisherQueueSize);
00116 service_servers_.push_back(node_handle_.advertiseService(
00117 kSubmapQueryServiceName, &Node::HandleSubmapQuery, this));
00118 service_servers_.push_back(node_handle_.advertiseService(
00119 kTrajectoryQueryServiceName, &Node::HandleTrajectoryQuery, this));
00120 service_servers_.push_back(node_handle_.advertiseService(
00121 kStartTrajectoryServiceName, &Node::HandleStartTrajectory, this));
00122 service_servers_.push_back(node_handle_.advertiseService(
00123 kFinishTrajectoryServiceName, &Node::HandleFinishTrajectory, this));
00124 service_servers_.push_back(node_handle_.advertiseService(
00125 kWriteStateServiceName, &Node::HandleWriteState, this));
00126 service_servers_.push_back(node_handle_.advertiseService(
00127 kGetTrajectoryStatesServiceName, &Node::HandleGetTrajectoryStates, this));
00128 service_servers_.push_back(node_handle_.advertiseService(
00129 kReadMetricsServiceName, &Node::HandleReadMetrics, this));
00130
00131 scan_matched_point_cloud_publisher_ =
00132 node_handle_.advertise<sensor_msgs::PointCloud2>(
00133 kScanMatchedPointCloudTopic, kLatestOnlyPublisherQueueSize);
00134
00135 wall_timers_.push_back(node_handle_.createWallTimer(
00136 ::ros::WallDuration(node_options_.submap_publish_period_sec),
00137 &Node::PublishSubmapList, this));
00138 if (node_options_.pose_publish_period_sec > 0) {
00139 publish_local_trajectory_data_timer_ = node_handle_.createTimer(
00140 ::ros::Duration(node_options_.pose_publish_period_sec),
00141 &Node::PublishLocalTrajectoryData, this);
00142 }
00143 wall_timers_.push_back(node_handle_.createWallTimer(
00144 ::ros::WallDuration(node_options_.trajectory_publish_period_sec),
00145 &Node::PublishTrajectoryNodeList, this));
00146 wall_timers_.push_back(node_handle_.createWallTimer(
00147 ::ros::WallDuration(node_options_.trajectory_publish_period_sec),
00148 &Node::PublishLandmarkPosesList, this));
00149 wall_timers_.push_back(node_handle_.createWallTimer(
00150 ::ros::WallDuration(kConstraintPublishPeriodSec),
00151 &Node::PublishConstraintList, this));
00152 }
00153
00154 Node::~Node() { FinishAllTrajectories(); }
00155
00156 ::ros::NodeHandle* Node::node_handle() { return &node_handle_; }
00157
00158 bool Node::HandleSubmapQuery(
00159 ::cartographer_ros_msgs::SubmapQuery::Request& request,
00160 ::cartographer_ros_msgs::SubmapQuery::Response& response) {
00161 absl::MutexLock lock(&mutex_);
00162 map_builder_bridge_.HandleSubmapQuery(request, response);
00163 return true;
00164 }
00165
00166 bool Node::HandleTrajectoryQuery(
00167 ::cartographer_ros_msgs::TrajectoryQuery::Request& request,
00168 ::cartographer_ros_msgs::TrajectoryQuery::Response& response) {
00169 absl::MutexLock lock(&mutex_);
00170 response.status = TrajectoryStateToStatus(
00171 request.trajectory_id,
00172 {TrajectoryState::ACTIVE, TrajectoryState::FINISHED,
00173 TrajectoryState::FROZEN} );
00174 if (response.status.code != cartographer_ros_msgs::StatusCode::OK) {
00175 LOG(ERROR) << "Can't query trajectory from pose graph: "
00176 << response.status.message;
00177 return true;
00178 }
00179 map_builder_bridge_.HandleTrajectoryQuery(request, response);
00180 return true;
00181 }
00182
00183 void Node::PublishSubmapList(const ::ros::WallTimerEvent& unused_timer_event) {
00184 absl::MutexLock lock(&mutex_);
00185 submap_list_publisher_.publish(map_builder_bridge_.GetSubmapList());
00186 }
00187
00188 void Node::AddExtrapolator(const int trajectory_id,
00189 const TrajectoryOptions& options) {
00190 constexpr double kExtrapolationEstimationTimeSec = 0.001;
00191 CHECK(extrapolators_.count(trajectory_id) == 0);
00192 const double gravity_time_constant =
00193 node_options_.map_builder_options.use_trajectory_builder_3d()
00194 ? options.trajectory_builder_options.trajectory_builder_3d_options()
00195 .imu_gravity_time_constant()
00196 : options.trajectory_builder_options.trajectory_builder_2d_options()
00197 .imu_gravity_time_constant();
00198 extrapolators_.emplace(
00199 std::piecewise_construct, std::forward_as_tuple(trajectory_id),
00200 std::forward_as_tuple(
00201 ::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
00202 gravity_time_constant));
00203 }
00204
00205 void Node::AddSensorSamplers(const int trajectory_id,
00206 const TrajectoryOptions& options) {
00207 CHECK(sensor_samplers_.count(trajectory_id) == 0);
00208 sensor_samplers_.emplace(
00209 std::piecewise_construct, std::forward_as_tuple(trajectory_id),
00210 std::forward_as_tuple(
00211 options.rangefinder_sampling_ratio, options.odometry_sampling_ratio,
00212 options.fixed_frame_pose_sampling_ratio, options.imu_sampling_ratio,
00213 options.landmarks_sampling_ratio));
00214 }
00215
00216 void Node::PublishLocalTrajectoryData(const ::ros::TimerEvent& timer_event) {
00217 absl::MutexLock lock(&mutex_);
00218 for (const auto& entry : map_builder_bridge_.GetLocalTrajectoryData()) {
00219 const auto& trajectory_data = entry.second;
00220
00221 auto& extrapolator = extrapolators_.at(entry.first);
00222
00223
00224 if (trajectory_data.local_slam_data->time !=
00225 extrapolator.GetLastPoseTime()) {
00226 if (scan_matched_point_cloud_publisher_.getNumSubscribers() > 0) {
00227
00228
00229 carto::sensor::TimedPointCloud point_cloud;
00230 point_cloud.reserve(trajectory_data.local_slam_data->range_data_in_local
00231 .returns.size());
00232 for (const cartographer::sensor::RangefinderPoint point :
00233 trajectory_data.local_slam_data->range_data_in_local.returns) {
00234 point_cloud.push_back(cartographer::sensor::ToTimedRangefinderPoint(
00235 point, 0.f ));
00236 }
00237 scan_matched_point_cloud_publisher_.publish(ToPointCloud2Message(
00238 carto::common::ToUniversal(trajectory_data.local_slam_data->time),
00239 node_options_.map_frame,
00240 carto::sensor::TransformTimedPointCloud(
00241 point_cloud, trajectory_data.local_to_map.cast<float>())));
00242 }
00243 extrapolator.AddPose(trajectory_data.local_slam_data->time,
00244 trajectory_data.local_slam_data->local_pose);
00245 }
00246
00247 geometry_msgs::TransformStamped stamped_transform;
00248
00249
00250
00251
00252 const ::cartographer::common::Time now = std::max(
00253 FromRos(ros::Time::now()), extrapolator.GetLastExtrapolatedTime());
00254 stamped_transform.header.stamp =
00255 node_options_.use_pose_extrapolator
00256 ? ToRos(now)
00257 : ToRos(trajectory_data.local_slam_data->time);
00258 const Rigid3d tracking_to_local_3d =
00259 node_options_.use_pose_extrapolator
00260 ? extrapolator.ExtrapolatePose(now)
00261 : trajectory_data.local_slam_data->local_pose;
00262 const Rigid3d tracking_to_local = [&] {
00263 if (trajectory_data.trajectory_options.publish_frame_projected_to_2d) {
00264 return carto::transform::Embed3D(
00265 carto::transform::Project2D(tracking_to_local_3d));
00266 }
00267 return tracking_to_local_3d;
00268 }();
00269
00270 const Rigid3d tracking_to_map =
00271 trajectory_data.local_to_map * tracking_to_local;
00272
00273 if (trajectory_data.published_to_tracking != nullptr) {
00274 if (trajectory_data.trajectory_options.provide_odom_frame) {
00275 std::vector<geometry_msgs::TransformStamped> stamped_transforms;
00276
00277 stamped_transform.header.frame_id = node_options_.map_frame;
00278 stamped_transform.child_frame_id =
00279 trajectory_data.trajectory_options.odom_frame;
00280 stamped_transform.transform =
00281 ToGeometryMsgTransform(trajectory_data.local_to_map);
00282 stamped_transforms.push_back(stamped_transform);
00283
00284 stamped_transform.header.frame_id =
00285 trajectory_data.trajectory_options.odom_frame;
00286 stamped_transform.child_frame_id =
00287 trajectory_data.trajectory_options.published_frame;
00288 stamped_transform.transform = ToGeometryMsgTransform(
00289 tracking_to_local * (*trajectory_data.published_to_tracking));
00290 stamped_transforms.push_back(stamped_transform);
00291
00292 tf_broadcaster_.sendTransform(stamped_transforms);
00293 } else {
00294 stamped_transform.header.frame_id = node_options_.map_frame;
00295 stamped_transform.child_frame_id =
00296 trajectory_data.trajectory_options.published_frame;
00297 stamped_transform.transform = ToGeometryMsgTransform(
00298 tracking_to_map * (*trajectory_data.published_to_tracking));
00299 tf_broadcaster_.sendTransform(stamped_transform);
00300 }
00301 }
00302 }
00303 }
00304
00305 void Node::PublishTrajectoryNodeList(
00306 const ::ros::WallTimerEvent& unused_timer_event) {
00307 if (trajectory_node_list_publisher_.getNumSubscribers() > 0) {
00308 absl::MutexLock lock(&mutex_);
00309 trajectory_node_list_publisher_.publish(
00310 map_builder_bridge_.GetTrajectoryNodeList());
00311 }
00312 }
00313
00314 void Node::PublishLandmarkPosesList(
00315 const ::ros::WallTimerEvent& unused_timer_event) {
00316 if (landmark_poses_list_publisher_.getNumSubscribers() > 0) {
00317 absl::MutexLock lock(&mutex_);
00318 landmark_poses_list_publisher_.publish(
00319 map_builder_bridge_.GetLandmarkPosesList());
00320 }
00321 }
00322
00323 void Node::PublishConstraintList(
00324 const ::ros::WallTimerEvent& unused_timer_event) {
00325 if (constraint_list_publisher_.getNumSubscribers() > 0) {
00326 absl::MutexLock lock(&mutex_);
00327 constraint_list_publisher_.publish(map_builder_bridge_.GetConstraintList());
00328 }
00329 }
00330
00331 std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
00332 Node::ComputeExpectedSensorIds(const TrajectoryOptions& options) const {
00333 using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
00334 using SensorType = SensorId::SensorType;
00335 std::set<SensorId> expected_topics;
00336
00337 for (const std::string& topic :
00338 ComputeRepeatedTopicNames(kLaserScanTopic, options.num_laser_scans)) {
00339 expected_topics.insert(SensorId{SensorType::RANGE, topic});
00340 }
00341 for (const std::string& topic : ComputeRepeatedTopicNames(
00342 kMultiEchoLaserScanTopic, options.num_multi_echo_laser_scans)) {
00343 expected_topics.insert(SensorId{SensorType::RANGE, topic});
00344 }
00345 for (const std::string& topic :
00346 ComputeRepeatedTopicNames(kPointCloud2Topic, options.num_point_clouds)) {
00347 expected_topics.insert(SensorId{SensorType::RANGE, topic});
00348 }
00349
00350
00351 if (node_options_.map_builder_options.use_trajectory_builder_3d() ||
00352 (node_options_.map_builder_options.use_trajectory_builder_2d() &&
00353 options.trajectory_builder_options.trajectory_builder_2d_options()
00354 .use_imu_data())) {
00355 expected_topics.insert(SensorId{SensorType::IMU, kImuTopic});
00356 }
00357
00358 if (options.use_odometry) {
00359 expected_topics.insert(SensorId{SensorType::ODOMETRY, kOdometryTopic});
00360 }
00361
00362 if (options.use_nav_sat) {
00363 expected_topics.insert(
00364 SensorId{SensorType::FIXED_FRAME_POSE, kNavSatFixTopic});
00365 }
00366
00367 if (options.use_landmarks) {
00368 expected_topics.insert(SensorId{SensorType::LANDMARK, kLandmarkTopic});
00369 }
00370 return expected_topics;
00371 }
00372
00373 int Node::AddTrajectory(const TrajectoryOptions& options) {
00374 const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
00375 expected_sensor_ids = ComputeExpectedSensorIds(options);
00376 const int trajectory_id =
00377 map_builder_bridge_.AddTrajectory(expected_sensor_ids, options);
00378 AddExtrapolator(trajectory_id, options);
00379 AddSensorSamplers(trajectory_id, options);
00380 LaunchSubscribers(options, trajectory_id);
00381 wall_timers_.push_back(node_handle_.createWallTimer(
00382 ::ros::WallDuration(kTopicMismatchCheckDelaySec),
00383 &Node::MaybeWarnAboutTopicMismatch, this, true));
00384 for (const auto& sensor_id : expected_sensor_ids) {
00385 subscribed_topics_.insert(sensor_id.id);
00386 }
00387 return trajectory_id;
00388 }
00389
00390 void Node::LaunchSubscribers(const TrajectoryOptions& options,
00391 const int trajectory_id) {
00392 for (const std::string& topic :
00393 ComputeRepeatedTopicNames(kLaserScanTopic, options.num_laser_scans)) {
00394 subscribers_[trajectory_id].push_back(
00395 {SubscribeWithHandler<sensor_msgs::LaserScan>(
00396 &Node::HandleLaserScanMessage, trajectory_id, topic, &node_handle_,
00397 this),
00398 topic});
00399 }
00400 for (const std::string& topic : ComputeRepeatedTopicNames(
00401 kMultiEchoLaserScanTopic, options.num_multi_echo_laser_scans)) {
00402 subscribers_[trajectory_id].push_back(
00403 {SubscribeWithHandler<sensor_msgs::MultiEchoLaserScan>(
00404 &Node::HandleMultiEchoLaserScanMessage, trajectory_id, topic,
00405 &node_handle_, this),
00406 topic});
00407 }
00408 for (const std::string& topic :
00409 ComputeRepeatedTopicNames(kPointCloud2Topic, options.num_point_clouds)) {
00410 subscribers_[trajectory_id].push_back(
00411 {SubscribeWithHandler<sensor_msgs::PointCloud2>(
00412 &Node::HandlePointCloud2Message, trajectory_id, topic,
00413 &node_handle_, this),
00414 topic});
00415 }
00416
00417
00418
00419 if (node_options_.map_builder_options.use_trajectory_builder_3d() ||
00420 (node_options_.map_builder_options.use_trajectory_builder_2d() &&
00421 options.trajectory_builder_options.trajectory_builder_2d_options()
00422 .use_imu_data())) {
00423 subscribers_[trajectory_id].push_back(
00424 {SubscribeWithHandler<sensor_msgs::Imu>(&Node::HandleImuMessage,
00425 trajectory_id, kImuTopic,
00426 &node_handle_, this),
00427 kImuTopic});
00428 }
00429
00430 if (options.use_odometry) {
00431 subscribers_[trajectory_id].push_back(
00432 {SubscribeWithHandler<nav_msgs::Odometry>(&Node::HandleOdometryMessage,
00433 trajectory_id, kOdometryTopic,
00434 &node_handle_, this),
00435 kOdometryTopic});
00436 }
00437 if (options.use_nav_sat) {
00438 subscribers_[trajectory_id].push_back(
00439 {SubscribeWithHandler<sensor_msgs::NavSatFix>(
00440 &Node::HandleNavSatFixMessage, trajectory_id, kNavSatFixTopic,
00441 &node_handle_, this),
00442 kNavSatFixTopic});
00443 }
00444 if (options.use_landmarks) {
00445 subscribers_[trajectory_id].push_back(
00446 {SubscribeWithHandler<cartographer_ros_msgs::LandmarkList>(
00447 &Node::HandleLandmarkMessage, trajectory_id, kLandmarkTopic,
00448 &node_handle_, this),
00449 kLandmarkTopic});
00450 }
00451 }
00452
00453 bool Node::ValidateTrajectoryOptions(const TrajectoryOptions& options) {
00454 if (node_options_.map_builder_options.use_trajectory_builder_2d()) {
00455 return options.trajectory_builder_options
00456 .has_trajectory_builder_2d_options();
00457 }
00458 if (node_options_.map_builder_options.use_trajectory_builder_3d()) {
00459 return options.trajectory_builder_options
00460 .has_trajectory_builder_3d_options();
00461 }
00462 return false;
00463 }
00464
00465 bool Node::ValidateTopicNames(const TrajectoryOptions& options) {
00466 for (const auto& sensor_id : ComputeExpectedSensorIds(options)) {
00467 const std::string& topic = sensor_id.id;
00468 if (subscribed_topics_.count(topic) > 0) {
00469 LOG(ERROR) << "Topic name [" << topic << "] is already used.";
00470 return false;
00471 }
00472 }
00473 return true;
00474 }
00475
00476 cartographer_ros_msgs::StatusResponse Node::TrajectoryStateToStatus(
00477 const int trajectory_id, const std::set<TrajectoryState>& valid_states) {
00478 const auto trajectory_states = map_builder_bridge_.GetTrajectoryStates();
00479 cartographer_ros_msgs::StatusResponse status_response;
00480
00481 const auto it = trajectory_states.find(trajectory_id);
00482 if (it == trajectory_states.end()) {
00483 status_response.message =
00484 absl::StrCat("Trajectory ", trajectory_id, " doesn't exist.");
00485 status_response.code = cartographer_ros_msgs::StatusCode::NOT_FOUND;
00486 return status_response;
00487 }
00488
00489 status_response.message =
00490 absl::StrCat("Trajectory ", trajectory_id, " is in '",
00491 TrajectoryStateToString(it->second), "' state.");
00492 status_response.code =
00493 valid_states.count(it->second)
00494 ? cartographer_ros_msgs::StatusCode::OK
00495 : cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
00496 return status_response;
00497 }
00498
00499 cartographer_ros_msgs::StatusResponse Node::FinishTrajectoryUnderLock(
00500 const int trajectory_id) {
00501 cartographer_ros_msgs::StatusResponse status_response;
00502 if (trajectories_scheduled_for_finish_.count(trajectory_id)) {
00503 status_response.message = absl::StrCat("Trajectory ", trajectory_id,
00504 " already pending to finish.");
00505 status_response.code = cartographer_ros_msgs::StatusCode::OK;
00506 LOG(INFO) << status_response.message;
00507 return status_response;
00508 }
00509
00510
00511 status_response = TrajectoryStateToStatus(
00512 trajectory_id, {TrajectoryState::ACTIVE} );
00513 if (status_response.code != cartographer_ros_msgs::StatusCode::OK) {
00514 LOG(ERROR) << "Can't finish trajectory: " << status_response.message;
00515 return status_response;
00516 }
00517
00518
00519
00520 if (subscribers_.count(trajectory_id)) {
00521 for (auto& entry : subscribers_[trajectory_id]) {
00522 entry.subscriber.shutdown();
00523 subscribed_topics_.erase(entry.topic);
00524 LOG(INFO) << "Shutdown the subscriber of [" << entry.topic << "]";
00525 }
00526 CHECK_EQ(subscribers_.erase(trajectory_id), 1);
00527 }
00528 map_builder_bridge_.FinishTrajectory(trajectory_id);
00529 trajectories_scheduled_for_finish_.emplace(trajectory_id);
00530 status_response.message =
00531 absl::StrCat("Finished trajectory ", trajectory_id, ".");
00532 status_response.code = cartographer_ros_msgs::StatusCode::OK;
00533 return status_response;
00534 }
00535
00536 bool Node::HandleStartTrajectory(
00537 ::cartographer_ros_msgs::StartTrajectory::Request& request,
00538 ::cartographer_ros_msgs::StartTrajectory::Response& response) {
00539 TrajectoryOptions trajectory_options;
00540 std::tie(std::ignore, trajectory_options) = LoadOptions(
00541 request.configuration_directory, request.configuration_basename);
00542
00543 if (request.use_initial_pose) {
00544 const auto pose = ToRigid3d(request.initial_pose);
00545 if (!pose.IsValid()) {
00546 response.status.message =
00547 "Invalid pose argument. Orientation quaternion must be normalized.";
00548 LOG(ERROR) << response.status.message;
00549 response.status.code =
00550 cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
00551 return true;
00552 }
00553
00554
00555 response.status = TrajectoryStateToStatus(
00556 request.relative_to_trajectory_id,
00557 {TrajectoryState::ACTIVE, TrajectoryState::FROZEN,
00558 TrajectoryState::FINISHED} );
00559 if (response.status.code != cartographer_ros_msgs::StatusCode::OK) {
00560 LOG(ERROR) << "Can't start a trajectory with initial pose: "
00561 << response.status.message;
00562 return true;
00563 }
00564
00565 ::cartographer::mapping::proto::InitialTrajectoryPose
00566 initial_trajectory_pose;
00567 initial_trajectory_pose.set_to_trajectory_id(
00568 request.relative_to_trajectory_id);
00569 *initial_trajectory_pose.mutable_relative_pose() =
00570 cartographer::transform::ToProto(pose);
00571 initial_trajectory_pose.set_timestamp(cartographer::common::ToUniversal(
00572 ::cartographer_ros::FromRos(ros::Time(0))));
00573 *trajectory_options.trajectory_builder_options
00574 .mutable_initial_trajectory_pose() = initial_trajectory_pose;
00575 }
00576
00577 if (!ValidateTrajectoryOptions(trajectory_options)) {
00578 response.status.message = "Invalid trajectory options.";
00579 LOG(ERROR) << response.status.message;
00580 response.status.code = cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
00581 } else if (!ValidateTopicNames(trajectory_options)) {
00582 response.status.message = "Topics are already used by another trajectory.";
00583 LOG(ERROR) << response.status.message;
00584 response.status.code = cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
00585 } else {
00586 response.status.message = "Success.";
00587 response.trajectory_id = AddTrajectory(trajectory_options);
00588 response.status.code = cartographer_ros_msgs::StatusCode::OK;
00589 }
00590 return true;
00591 }
00592
00593 void Node::StartTrajectoryWithDefaultTopics(const TrajectoryOptions& options) {
00594 absl::MutexLock lock(&mutex_);
00595 CHECK(ValidateTrajectoryOptions(options));
00596 AddTrajectory(options);
00597 }
00598
00599 std::vector<
00600 std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>>
00601 Node::ComputeDefaultSensorIdsForMultipleBags(
00602 const std::vector<TrajectoryOptions>& bags_options) const {
00603 using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
00604 std::vector<std::set<SensorId>> bags_sensor_ids;
00605 for (size_t i = 0; i < bags_options.size(); ++i) {
00606 std::string prefix;
00607 if (bags_options.size() > 1) {
00608 prefix = "bag_" + std::to_string(i + 1) + "_";
00609 }
00610 std::set<SensorId> unique_sensor_ids;
00611 for (const auto& sensor_id : ComputeExpectedSensorIds(bags_options.at(i))) {
00612 unique_sensor_ids.insert(SensorId{sensor_id.type, prefix + sensor_id.id});
00613 }
00614 bags_sensor_ids.push_back(unique_sensor_ids);
00615 }
00616 return bags_sensor_ids;
00617 }
00618
00619 int Node::AddOfflineTrajectory(
00620 const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>&
00621 expected_sensor_ids,
00622 const TrajectoryOptions& options) {
00623 absl::MutexLock lock(&mutex_);
00624 const int trajectory_id =
00625 map_builder_bridge_.AddTrajectory(expected_sensor_ids, options);
00626 AddExtrapolator(trajectory_id, options);
00627 AddSensorSamplers(trajectory_id, options);
00628 return trajectory_id;
00629 }
00630
00631 bool Node::HandleGetTrajectoryStates(
00632 ::cartographer_ros_msgs::GetTrajectoryStates::Request& request,
00633 ::cartographer_ros_msgs::GetTrajectoryStates::Response& response) {
00634 using TrajectoryState =
00635 ::cartographer::mapping::PoseGraphInterface::TrajectoryState;
00636 absl::MutexLock lock(&mutex_);
00637 response.status.code = ::cartographer_ros_msgs::StatusCode::OK;
00638 response.trajectory_states.header.stamp = ros::Time::now();
00639 for (const auto& entry : map_builder_bridge_.GetTrajectoryStates()) {
00640 response.trajectory_states.trajectory_id.push_back(entry.first);
00641 switch (entry.second) {
00642 case TrajectoryState::ACTIVE:
00643 response.trajectory_states.trajectory_state.push_back(
00644 ::cartographer_ros_msgs::TrajectoryStates::ACTIVE);
00645 break;
00646 case TrajectoryState::FINISHED:
00647 response.trajectory_states.trajectory_state.push_back(
00648 ::cartographer_ros_msgs::TrajectoryStates::FINISHED);
00649 break;
00650 case TrajectoryState::FROZEN:
00651 response.trajectory_states.trajectory_state.push_back(
00652 ::cartographer_ros_msgs::TrajectoryStates::FROZEN);
00653 break;
00654 case TrajectoryState::DELETED:
00655 response.trajectory_states.trajectory_state.push_back(
00656 ::cartographer_ros_msgs::TrajectoryStates::DELETED);
00657 break;
00658 }
00659 }
00660 return true;
00661 }
00662
00663 bool Node::HandleFinishTrajectory(
00664 ::cartographer_ros_msgs::FinishTrajectory::Request& request,
00665 ::cartographer_ros_msgs::FinishTrajectory::Response& response) {
00666 absl::MutexLock lock(&mutex_);
00667 response.status = FinishTrajectoryUnderLock(request.trajectory_id);
00668 return true;
00669 }
00670
00671 bool Node::HandleWriteState(
00672 ::cartographer_ros_msgs::WriteState::Request& request,
00673 ::cartographer_ros_msgs::WriteState::Response& response) {
00674 absl::MutexLock lock(&mutex_);
00675 if (map_builder_bridge_.SerializeState(request.filename,
00676 request.include_unfinished_submaps)) {
00677 response.status.code = cartographer_ros_msgs::StatusCode::OK;
00678 response.status.message =
00679 absl::StrCat("State written to '", request.filename, "'.");
00680 } else {
00681 response.status.code = cartographer_ros_msgs::StatusCode::INVALID_ARGUMENT;
00682 response.status.message =
00683 absl::StrCat("Failed to write '", request.filename, "'.");
00684 }
00685 return true;
00686 }
00687
00688 bool Node::HandleReadMetrics(
00689 ::cartographer_ros_msgs::ReadMetrics::Request& request,
00690 ::cartographer_ros_msgs::ReadMetrics::Response& response) {
00691 absl::MutexLock lock(&mutex_);
00692 response.timestamp = ros::Time::now();
00693 if (!metrics_registry_) {
00694 response.status.code = cartographer_ros_msgs::StatusCode::UNAVAILABLE;
00695 response.status.message = "Collection of runtime metrics is not activated.";
00696 return true;
00697 }
00698 metrics_registry_->ReadMetrics(&response);
00699 response.status.code = cartographer_ros_msgs::StatusCode::OK;
00700 response.status.message = "Successfully read metrics.";
00701 return true;
00702 }
00703
00704 void Node::FinishAllTrajectories() {
00705 absl::MutexLock lock(&mutex_);
00706 for (const auto& entry : map_builder_bridge_.GetTrajectoryStates()) {
00707 if (entry.second == TrajectoryState::ACTIVE) {
00708 const int trajectory_id = entry.first;
00709 CHECK_EQ(FinishTrajectoryUnderLock(trajectory_id).code,
00710 cartographer_ros_msgs::StatusCode::OK);
00711 }
00712 }
00713 }
00714
00715 bool Node::FinishTrajectory(const int trajectory_id) {
00716 absl::MutexLock lock(&mutex_);
00717 return FinishTrajectoryUnderLock(trajectory_id).code ==
00718 cartographer_ros_msgs::StatusCode::OK;
00719 }
00720
00721 void Node::RunFinalOptimization() {
00722 {
00723 for (const auto& entry : map_builder_bridge_.GetTrajectoryStates()) {
00724 const int trajectory_id = entry.first;
00725 if (entry.second == TrajectoryState::ACTIVE) {
00726 LOG(WARNING)
00727 << "Can't run final optimization if there are one or more active "
00728 "trajectories. Trying to finish trajectory with ID "
00729 << std::to_string(trajectory_id) << " now.";
00730 CHECK(FinishTrajectory(trajectory_id))
00731 << "Failed to finish trajectory with ID "
00732 << std::to_string(trajectory_id) << ".";
00733 }
00734 }
00735 }
00736
00737
00738 map_builder_bridge_.RunFinalOptimization();
00739 }
00740
00741 void Node::HandleOdometryMessage(const int trajectory_id,
00742 const std::string& sensor_id,
00743 const nav_msgs::Odometry::ConstPtr& msg) {
00744 absl::MutexLock lock(&mutex_);
00745 if (!sensor_samplers_.at(trajectory_id).odometry_sampler.Pulse()) {
00746 return;
00747 }
00748 auto sensor_bridge_ptr = map_builder_bridge_.sensor_bridge(trajectory_id);
00749 auto odometry_data_ptr = sensor_bridge_ptr->ToOdometryData(msg);
00750 if (odometry_data_ptr != nullptr) {
00751 extrapolators_.at(trajectory_id).AddOdometryData(*odometry_data_ptr);
00752 }
00753 sensor_bridge_ptr->HandleOdometryMessage(sensor_id, msg);
00754 }
00755
00756 void Node::HandleNavSatFixMessage(const int trajectory_id,
00757 const std::string& sensor_id,
00758 const sensor_msgs::NavSatFix::ConstPtr& msg) {
00759 absl::MutexLock lock(&mutex_);
00760 if (!sensor_samplers_.at(trajectory_id).fixed_frame_pose_sampler.Pulse()) {
00761 return;
00762 }
00763 map_builder_bridge_.sensor_bridge(trajectory_id)
00764 ->HandleNavSatFixMessage(sensor_id, msg);
00765 }
00766
00767 void Node::HandleLandmarkMessage(
00768 const int trajectory_id, const std::string& sensor_id,
00769 const cartographer_ros_msgs::LandmarkList::ConstPtr& msg) {
00770 absl::MutexLock lock(&mutex_);
00771 if (!sensor_samplers_.at(trajectory_id).landmark_sampler.Pulse()) {
00772 return;
00773 }
00774 map_builder_bridge_.sensor_bridge(trajectory_id)
00775 ->HandleLandmarkMessage(sensor_id, msg);
00776 }
00777
00778 void Node::HandleImuMessage(const int trajectory_id,
00779 const std::string& sensor_id,
00780 const sensor_msgs::Imu::ConstPtr& msg) {
00781 absl::MutexLock lock(&mutex_);
00782 if (!sensor_samplers_.at(trajectory_id).imu_sampler.Pulse()) {
00783 return;
00784 }
00785 auto sensor_bridge_ptr = map_builder_bridge_.sensor_bridge(trajectory_id);
00786 auto imu_data_ptr = sensor_bridge_ptr->ToImuData(msg);
00787 if (imu_data_ptr != nullptr) {
00788 extrapolators_.at(trajectory_id).AddImuData(*imu_data_ptr);
00789 }
00790 sensor_bridge_ptr->HandleImuMessage(sensor_id, msg);
00791 }
00792
00793 void Node::HandleLaserScanMessage(const int trajectory_id,
00794 const std::string& sensor_id,
00795 const sensor_msgs::LaserScan::ConstPtr& msg) {
00796 absl::MutexLock lock(&mutex_);
00797 if (!sensor_samplers_.at(trajectory_id).rangefinder_sampler.Pulse()) {
00798 return;
00799 }
00800 map_builder_bridge_.sensor_bridge(trajectory_id)
00801 ->HandleLaserScanMessage(sensor_id, msg);
00802 }
00803
00804 void Node::HandleMultiEchoLaserScanMessage(
00805 const int trajectory_id, const std::string& sensor_id,
00806 const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg) {
00807 absl::MutexLock lock(&mutex_);
00808 if (!sensor_samplers_.at(trajectory_id).rangefinder_sampler.Pulse()) {
00809 return;
00810 }
00811 map_builder_bridge_.sensor_bridge(trajectory_id)
00812 ->HandleMultiEchoLaserScanMessage(sensor_id, msg);
00813 }
00814
00815 void Node::HandlePointCloud2Message(
00816 const int trajectory_id, const std::string& sensor_id,
00817 const sensor_msgs::PointCloud2::ConstPtr& msg) {
00818 absl::MutexLock lock(&mutex_);
00819 if (!sensor_samplers_.at(trajectory_id).rangefinder_sampler.Pulse()) {
00820 return;
00821 }
00822 map_builder_bridge_.sensor_bridge(trajectory_id)
00823 ->HandlePointCloud2Message(sensor_id, msg);
00824 }
00825
00826 void Node::SerializeState(const std::string& filename,
00827 const bool include_unfinished_submaps) {
00828 absl::MutexLock lock(&mutex_);
00829 CHECK(
00830 map_builder_bridge_.SerializeState(filename, include_unfinished_submaps))
00831 << "Could not write state.";
00832 }
00833
00834 void Node::LoadState(const std::string& state_filename,
00835 const bool load_frozen_state) {
00836 absl::MutexLock lock(&mutex_);
00837 map_builder_bridge_.LoadState(state_filename, load_frozen_state);
00838 }
00839
00840 void Node::MaybeWarnAboutTopicMismatch(
00841 const ::ros::WallTimerEvent& unused_timer_event) {
00842 ::ros::master::V_TopicInfo ros_topics;
00843 ::ros::master::getTopics(ros_topics);
00844 std::set<std::string> published_topics;
00845 std::stringstream published_topics_string;
00846 for (const auto& it : ros_topics) {
00847 std::string resolved_topic = node_handle_.resolveName(it.name, false);
00848 published_topics.insert(resolved_topic);
00849 published_topics_string << resolved_topic << ",";
00850 }
00851 bool print_topics = false;
00852 for (const auto& entry : subscribers_) {
00853 int trajectory_id = entry.first;
00854 for (const auto& subscriber : entry.second) {
00855 std::string resolved_topic = node_handle_.resolveName(subscriber.topic);
00856 if (published_topics.count(resolved_topic) == 0) {
00857 LOG(WARNING) << "Expected topic \"" << subscriber.topic
00858 << "\" (trajectory " << trajectory_id << ")"
00859 << " (resolved topic \"" << resolved_topic << "\")"
00860 << " but no publisher is currently active.";
00861 print_topics = true;
00862 }
00863 }
00864 }
00865 if (print_topics) {
00866 LOG(WARNING) << "Currently available topics are: "
00867 << published_topics_string.str();
00868 }
00869 }
00870
00871 }