map_builder_bridge.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
20 #include "cartographer/io/color.h"
24 #include "cartographer_ros_msgs/StatusCode.h"
25 #include "cartographer_ros_msgs/StatusResponse.h"
26 
27 namespace cartographer_ros {
28 namespace {
29 
30 using ::cartographer::transform::Rigid3d;
31 
32 constexpr double kTrajectoryLineStripMarkerScale = 0.07;
33 constexpr double kLandmarkMarkerScale = 0.3;
34 constexpr double kConstraintMarkerScale = 0.025;
35 
36 ::std_msgs::ColorRGBA ToMessage(const cartographer::io::FloatColor& color) {
37  ::std_msgs::ColorRGBA result;
38  result.r = color[0];
39  result.g = color[1];
40  result.b = color[2];
41  result.a = 1.f;
42  return result;
43 }
44 
45 visualization_msgs::Marker CreateTrajectoryMarker(const int trajectory_id,
46  const std::string& frame_id) {
47  visualization_msgs::Marker marker;
48  marker.ns = "Trajectory " + std::to_string(trajectory_id);
49  marker.id = 0;
50  marker.type = visualization_msgs::Marker::LINE_STRIP;
51  marker.header.stamp = ::ros::Time::now();
52  marker.header.frame_id = frame_id;
53  marker.color = ToMessage(cartographer::io::GetColor(trajectory_id));
54  marker.scale.x = kTrajectoryLineStripMarkerScale;
55  marker.pose.orientation.w = 1.;
56  marker.pose.position.z = 0.05;
57  return marker;
58 }
59 
60 int GetLandmarkIndex(
61  const std::string& landmark_id,
62  std::unordered_map<std::string, int>* landmark_id_to_index) {
63  auto it = landmark_id_to_index->find(landmark_id);
64  if (it == landmark_id_to_index->end()) {
65  const int new_index = landmark_id_to_index->size();
66  landmark_id_to_index->emplace(landmark_id, new_index);
67  return new_index;
68  }
69  return it->second;
70 }
71 
72 visualization_msgs::Marker CreateLandmarkMarker(int landmark_index,
73  const Rigid3d& landmark_pose,
74  const std::string& frame_id) {
75  visualization_msgs::Marker marker;
76  marker.ns = "Landmarks";
77  marker.id = landmark_index;
78  marker.type = visualization_msgs::Marker::CUBE;
79  marker.header.stamp = ::ros::Time::now();
80  marker.header.frame_id = frame_id;
81  marker.scale.x = kLandmarkMarkerScale;
82  marker.scale.y = kLandmarkMarkerScale;
83  marker.scale.z = kLandmarkMarkerScale;
84  marker.color = ToMessage(cartographer::io::GetColor(landmark_index));
85  marker.pose = ToGeometryMsgPose(landmark_pose);
86  return marker;
87 }
88 
89 void PushAndResetLineMarker(visualization_msgs::Marker* marker,
90  std::vector<visualization_msgs::Marker>* markers) {
91  markers->push_back(*marker);
92  ++marker->id;
93  marker->points.clear();
94 }
95 
96 } // namespace
97 
99  const NodeOptions& node_options,
100  std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
101  tf2_ros::Buffer* const tf_buffer)
102  : node_options_(node_options),
103  map_builder_(std::move(map_builder)),
104  tf_buffer_(tf_buffer) {}
105 
106 void MapBuilderBridge::LoadState(const std::string& state_filename,
107  bool load_frozen_state) {
108  // Check if suffix of the state file is ".pbstream".
109  const std::string suffix = ".pbstream";
110  CHECK_EQ(state_filename.substr(
111  std::max<int>(state_filename.size() - suffix.size(), 0)),
112  suffix)
113  << "The file containing the state to be loaded must be a "
114  ".pbstream file.";
115  LOG(INFO) << "Loading saved state '" << state_filename << "'...";
116  cartographer::io::ProtoStreamReader stream(state_filename);
117  map_builder_->LoadState(&stream, load_frozen_state);
118 }
119 
121  const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>&
122  expected_sensor_ids,
123  const TrajectoryOptions& trajectory_options) {
124  const int trajectory_id = map_builder_->AddTrajectoryBuilder(
125  expected_sensor_ids, trajectory_options.trajectory_builder_options,
126  ::std::bind(&MapBuilderBridge::OnLocalSlamResult, this,
127  ::std::placeholders::_1, ::std::placeholders::_2,
128  ::std::placeholders::_3, ::std::placeholders::_4,
129  ::std::placeholders::_5));
130  LOG(INFO) << "Added trajectory with ID '" << trajectory_id << "'.";
131 
132  // Make sure there is no trajectory with 'trajectory_id' yet.
133  CHECK_EQ(sensor_bridges_.count(trajectory_id), 0);
134  sensor_bridges_[trajectory_id] =
135  cartographer::common::make_unique<SensorBridge>(
136  trajectory_options.num_subdivisions_per_laser_scan,
137  trajectory_options.tracking_frame,
139  map_builder_->GetTrajectoryBuilder(trajectory_id));
140  auto emplace_result =
141  trajectory_options_.emplace(trajectory_id, trajectory_options);
142  CHECK(emplace_result.second == true);
143  return trajectory_id;
144 }
145 
146 void MapBuilderBridge::FinishTrajectory(const int trajectory_id) {
147  LOG(INFO) << "Finishing trajectory with ID '" << trajectory_id << "'...";
148 
149  // Make sure there is a trajectory with 'trajectory_id'.
150  CHECK_EQ(sensor_bridges_.count(trajectory_id), 1);
151  map_builder_->FinishTrajectory(trajectory_id);
152  sensor_bridges_.erase(trajectory_id);
153 }
154 
156  LOG(INFO) << "Running final trajectory optimization...";
157  map_builder_->pose_graph()->RunFinalOptimization();
158 }
159 
160 bool MapBuilderBridge::SerializeState(const std::string& filename) {
161  cartographer::io::ProtoStreamWriter writer(filename);
162  map_builder_->SerializeState(&writer);
163  return writer.Close();
164 }
165 
167  cartographer_ros_msgs::SubmapQuery::Request& request,
168  cartographer_ros_msgs::SubmapQuery::Response& response) {
169  cartographer::mapping::proto::SubmapQuery::Response response_proto;
171  request.submap_index};
172  const std::string error =
173  map_builder_->SubmapToProto(submap_id, &response_proto);
174  if (!error.empty()) {
175  LOG(ERROR) << error;
176  response.status.code = cartographer_ros_msgs::StatusCode::NOT_FOUND;
177  response.status.message = error;
178  return;
179  }
180 
181  response.submap_version = response_proto.submap_version();
182  for (const auto& texture_proto : response_proto.textures()) {
183  response.textures.emplace_back();
184  auto& texture = response.textures.back();
185  texture.cells.insert(texture.cells.begin(), texture_proto.cells().begin(),
186  texture_proto.cells().end());
187  texture.width = texture_proto.width();
188  texture.height = texture_proto.height();
189  texture.resolution = texture_proto.resolution();
190  texture.slice_pose = ToGeometryMsgPose(
191  cartographer::transform::ToRigid3(texture_proto.slice_pose()));
192  }
193  response.status.message = "Success.";
194  response.status.code = cartographer_ros_msgs::StatusCode::OK;
195 }
196 
198  std::set<int> frozen_trajectory_ids;
199  const auto node_poses = map_builder_->pose_graph()->GetTrajectoryNodePoses();
200  for (const int trajectory_id : node_poses.trajectory_ids()) {
201  if (map_builder_->pose_graph()->IsTrajectoryFrozen(trajectory_id)) {
202  frozen_trajectory_ids.insert(trajectory_id);
203  }
204  }
205  return frozen_trajectory_ids;
206 }
207 
208 cartographer_ros_msgs::SubmapList MapBuilderBridge::GetSubmapList() {
209  cartographer_ros_msgs::SubmapList submap_list;
210  submap_list.header.stamp = ::ros::Time::now();
211  submap_list.header.frame_id = node_options_.map_frame;
212  for (const auto& submap_id_pose :
213  map_builder_->pose_graph()->GetAllSubmapPoses()) {
214  cartographer_ros_msgs::SubmapEntry submap_entry;
215  submap_entry.trajectory_id = submap_id_pose.id.trajectory_id;
216  submap_entry.submap_index = submap_id_pose.id.submap_index;
217  submap_entry.submap_version = submap_id_pose.data.version;
218  submap_entry.pose = ToGeometryMsgPose(submap_id_pose.data.pose);
219  submap_list.submap.push_back(submap_entry);
220  }
221  return submap_list;
222 }
223 
224 std::unordered_map<int, MapBuilderBridge::TrajectoryState>
226  std::unordered_map<int, TrajectoryState> trajectory_states;
227  for (const auto& entry : sensor_bridges_) {
228  const int trajectory_id = entry.first;
229  const SensorBridge& sensor_bridge = *entry.second;
230 
231  std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data;
232  {
234  if (trajectory_state_data_.count(trajectory_id) == 0) {
235  continue;
236  }
237  local_slam_data = trajectory_state_data_.at(trajectory_id);
238  }
239 
240  // Make sure there is a trajectory with 'trajectory_id'.
241  CHECK_EQ(trajectory_options_.count(trajectory_id), 1);
242  trajectory_states[trajectory_id] = {
243  local_slam_data,
244  map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id),
245  sensor_bridge.tf_bridge().LookupToTracking(
246  local_slam_data->time,
247  trajectory_options_[trajectory_id].published_frame),
248  trajectory_options_[trajectory_id]};
249  }
250  return trajectory_states;
251 }
252 
253 visualization_msgs::MarkerArray MapBuilderBridge::GetTrajectoryNodeList() {
254  visualization_msgs::MarkerArray trajectory_node_list;
255  const auto node_poses = map_builder_->pose_graph()->GetTrajectoryNodePoses();
256  // Find the last node indices for each trajectory that have either
257  // inter-submap or inter-trajectory constraints.
258  std::map<int, int /* node_index */>
259  trajectory_to_last_inter_submap_constrained_node;
260  std::map<int, int /* node_index */>
261  trajectory_to_last_inter_trajectory_constrained_node;
262  for (const int trajectory_id : node_poses.trajectory_ids()) {
263  trajectory_to_last_inter_submap_constrained_node[trajectory_id] = 0;
264  trajectory_to_last_inter_trajectory_constrained_node[trajectory_id] = 0;
265  }
266  const auto constraints = map_builder_->pose_graph()->constraints();
267  for (const auto& constraint : constraints) {
268  if (constraint.tag ==
269  cartographer::mapping::PoseGraph::Constraint::INTER_SUBMAP) {
270  if (constraint.node_id.trajectory_id ==
271  constraint.submap_id.trajectory_id) {
272  trajectory_to_last_inter_submap_constrained_node[constraint.node_id
273  .trajectory_id] =
274  std::max(trajectory_to_last_inter_submap_constrained_node.at(
275  constraint.node_id.trajectory_id),
276  constraint.node_id.node_index);
277  } else {
278  trajectory_to_last_inter_trajectory_constrained_node
279  [constraint.node_id.trajectory_id] =
280  std::max(trajectory_to_last_inter_submap_constrained_node.at(
281  constraint.node_id.trajectory_id),
282  constraint.node_id.node_index);
283  }
284  }
285  }
286 
287  for (const int trajectory_id : node_poses.trajectory_ids()) {
288  visualization_msgs::Marker marker =
289  CreateTrajectoryMarker(trajectory_id, node_options_.map_frame);
290  int last_inter_submap_constrained_node = std::max(
291  node_poses.trajectory(trajectory_id).begin()->id.node_index,
292  trajectory_to_last_inter_submap_constrained_node.at(trajectory_id));
293  int last_inter_trajectory_constrained_node = std::max(
294  node_poses.trajectory(trajectory_id).begin()->id.node_index,
295  trajectory_to_last_inter_trajectory_constrained_node.at(trajectory_id));
296  last_inter_submap_constrained_node =
297  std::max(last_inter_submap_constrained_node,
298  last_inter_trajectory_constrained_node);
299 
300  if (map_builder_->pose_graph()->IsTrajectoryFrozen(trajectory_id)) {
301  last_inter_submap_constrained_node =
302  (--node_poses.trajectory(trajectory_id).end())->id.node_index;
303  last_inter_trajectory_constrained_node =
304  last_inter_submap_constrained_node;
305  }
306 
307  marker.color.a = 1.0;
308  for (const auto& node_id_data : node_poses.trajectory(trajectory_id)) {
309  if (!node_id_data.data.constant_pose_data.has_value()) {
310  PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
311  continue;
312  }
313  const ::geometry_msgs::Point node_point =
314  ToGeometryMsgPoint(node_id_data.data.global_pose.translation());
315  marker.points.push_back(node_point);
316 
317  if (node_id_data.id.node_index ==
318  last_inter_trajectory_constrained_node) {
319  PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
320  marker.points.push_back(node_point);
321  marker.color.a = 0.5;
322  }
323  if (node_id_data.id.node_index == last_inter_submap_constrained_node) {
324  PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
325  marker.points.push_back(node_point);
326  marker.color.a = 0.25;
327  }
328  // Work around the 16384 point limit in RViz by splitting the
329  // trajectory into multiple markers.
330  if (marker.points.size() == 16384) {
331  PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
332  // Push back the last point, so the two markers appear connected.
333  marker.points.push_back(node_point);
334  }
335  }
336  PushAndResetLineMarker(&marker, &trajectory_node_list.markers);
337  size_t current_last_marker_id = static_cast<size_t>(marker.id - 1);
338  if (trajectory_to_highest_marker_id_.count(trajectory_id) == 0) {
339  trajectory_to_highest_marker_id_[trajectory_id] = current_last_marker_id;
340  } else {
341  marker.action = visualization_msgs::Marker::DELETE;
342  while (static_cast<size_t>(marker.id) <=
343  trajectory_to_highest_marker_id_[trajectory_id]) {
344  trajectory_node_list.markers.push_back(marker);
345  ++marker.id;
346  }
347  trajectory_to_highest_marker_id_[trajectory_id] = current_last_marker_id;
348  }
349  }
350  return trajectory_node_list;
351 }
352 
353 visualization_msgs::MarkerArray MapBuilderBridge::GetLandmarkPosesList() {
354  visualization_msgs::MarkerArray landmark_poses_list;
355  const std::map<std::string, Rigid3d> landmark_poses =
356  map_builder_->pose_graph()->GetLandmarkPoses();
357  for (const auto& id_to_pose : landmark_poses) {
358  landmark_poses_list.markers.push_back(CreateLandmarkMarker(
359  GetLandmarkIndex(id_to_pose.first, &landmark_to_index_),
360  id_to_pose.second, node_options_.map_frame));
361  }
362  return landmark_poses_list;
363 }
364 
365 visualization_msgs::MarkerArray MapBuilderBridge::GetConstraintList() {
366  visualization_msgs::MarkerArray constraint_list;
367  int marker_id = 0;
368  visualization_msgs::Marker constraint_intra_marker;
369  constraint_intra_marker.id = marker_id++;
370  constraint_intra_marker.ns = "Intra constraints";
371  constraint_intra_marker.type = visualization_msgs::Marker::LINE_LIST;
372  constraint_intra_marker.header.stamp = ros::Time::now();
373  constraint_intra_marker.header.frame_id = node_options_.map_frame;
374  constraint_intra_marker.scale.x = kConstraintMarkerScale;
375  constraint_intra_marker.pose.orientation.w = 1.0;
376 
377  visualization_msgs::Marker residual_intra_marker = constraint_intra_marker;
378  residual_intra_marker.id = marker_id++;
379  residual_intra_marker.ns = "Intra residuals";
380  // This and other markers which are less numerous are set to be slightly
381  // above the intra constraints marker in order to ensure that they are
382  // visible.
383  residual_intra_marker.pose.position.z = 0.1;
384 
385  visualization_msgs::Marker constraint_inter_same_trajectory_marker =
386  constraint_intra_marker;
387  constraint_inter_same_trajectory_marker.id = marker_id++;
388  constraint_inter_same_trajectory_marker.ns =
389  "Inter constraints, same trajectory";
390  constraint_inter_same_trajectory_marker.pose.position.z = 0.1;
391 
392  visualization_msgs::Marker residual_inter_same_trajectory_marker =
393  constraint_intra_marker;
394  residual_inter_same_trajectory_marker.id = marker_id++;
395  residual_inter_same_trajectory_marker.ns = "Inter residuals, same trajectory";
396  residual_inter_same_trajectory_marker.pose.position.z = 0.1;
397 
398  visualization_msgs::Marker constraint_inter_diff_trajectory_marker =
399  constraint_intra_marker;
400  constraint_inter_diff_trajectory_marker.id = marker_id++;
401  constraint_inter_diff_trajectory_marker.ns =
402  "Inter constraints, different trajectories";
403  constraint_inter_diff_trajectory_marker.pose.position.z = 0.1;
404 
405  visualization_msgs::Marker residual_inter_diff_trajectory_marker =
406  constraint_intra_marker;
407  residual_inter_diff_trajectory_marker.id = marker_id++;
408  residual_inter_diff_trajectory_marker.ns =
409  "Inter residuals, different trajectories";
410  residual_inter_diff_trajectory_marker.pose.position.z = 0.1;
411 
412  const auto trajectory_node_poses =
413  map_builder_->pose_graph()->GetTrajectoryNodePoses();
414  const auto submap_poses = map_builder_->pose_graph()->GetAllSubmapPoses();
415  const auto constraints = map_builder_->pose_graph()->constraints();
416 
417  for (const auto& constraint : constraints) {
418  visualization_msgs::Marker *constraint_marker, *residual_marker;
419  std_msgs::ColorRGBA color_constraint, color_residual;
420  if (constraint.tag ==
421  cartographer::mapping::PoseGraph::Constraint::INTRA_SUBMAP) {
422  constraint_marker = &constraint_intra_marker;
423  residual_marker = &residual_intra_marker;
424  // Color mapping for submaps of various trajectories - add trajectory id
425  // to ensure different starting colors. Also add a fixed offset of 25
426  // to avoid having identical colors as trajectories.
427  color_constraint = ToMessage(
428  cartographer::io::GetColor(constraint.submap_id.submap_index +
429  constraint.submap_id.trajectory_id + 25));
430  color_residual.a = 1.0;
431  color_residual.r = 1.0;
432  } else {
433  if (constraint.node_id.trajectory_id ==
434  constraint.submap_id.trajectory_id) {
435  constraint_marker = &constraint_inter_same_trajectory_marker;
436  residual_marker = &residual_inter_same_trajectory_marker;
437  // Bright yellow
438  color_constraint.a = 1.0;
439  color_constraint.r = color_constraint.g = 1.0;
440  } else {
441  constraint_marker = &constraint_inter_diff_trajectory_marker;
442  residual_marker = &residual_inter_diff_trajectory_marker;
443  // Bright orange
444  color_constraint.a = 1.0;
445  color_constraint.r = 1.0;
446  color_constraint.g = 165. / 255.;
447  }
448  // Bright cyan
449  color_residual.a = 1.0;
450  color_residual.b = color_residual.g = 1.0;
451  }
452 
453  for (int i = 0; i < 2; ++i) {
454  constraint_marker->colors.push_back(color_constraint);
455  residual_marker->colors.push_back(color_residual);
456  }
457 
458  const auto submap_it = submap_poses.find(constraint.submap_id);
459  if (submap_it == submap_poses.end()) {
460  continue;
461  }
462  const auto& submap_pose = submap_it->data.pose;
463  const auto node_it = trajectory_node_poses.find(constraint.node_id);
464  if (node_it == trajectory_node_poses.end()) {
465  continue;
466  }
467  const auto& trajectory_node_pose = node_it->data.global_pose;
468  const Rigid3d constraint_pose = submap_pose * constraint.pose.zbar_ij;
469 
470  constraint_marker->points.push_back(
471  ToGeometryMsgPoint(submap_pose.translation()));
472  constraint_marker->points.push_back(
473  ToGeometryMsgPoint(constraint_pose.translation()));
474 
475  residual_marker->points.push_back(
476  ToGeometryMsgPoint(constraint_pose.translation()));
477  residual_marker->points.push_back(
478  ToGeometryMsgPoint(trajectory_node_pose.translation()));
479  }
480 
481  constraint_list.markers.push_back(constraint_intra_marker);
482  constraint_list.markers.push_back(residual_intra_marker);
483  constraint_list.markers.push_back(constraint_inter_same_trajectory_marker);
484  constraint_list.markers.push_back(residual_inter_same_trajectory_marker);
485  constraint_list.markers.push_back(constraint_inter_diff_trajectory_marker);
486  constraint_list.markers.push_back(residual_inter_diff_trajectory_marker);
487  return constraint_list;
488 }
489 
491  return sensor_bridges_.at(trajectory_id).get();
492 }
493 
495  const int trajectory_id, const ::cartographer::common::Time time,
496  const Rigid3d local_pose,
497  ::cartographer::sensor::RangeData range_data_in_local,
498  const std::unique_ptr<const ::cartographer::mapping::
499  TrajectoryBuilderInterface::InsertionResult>) {
500  std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data =
501  std::make_shared<TrajectoryState::LocalSlamData>(
502  TrajectoryState::LocalSlamData{time, local_pose,
503  std::move(range_data_in_local)});
505  trajectory_state_data_[trajectory_id] = std::move(local_slam_data);
506 }
507 
508 } // namespace cartographer_ros
std::unordered_map< int, size_t > trajectory_to_highest_marker_id_
visualization_msgs::MarkerArray GetTrajectoryNodeList()
visualization_msgs::MarkerArray GetConstraintList()
geometry_msgs::Pose ToGeometryMsgPose(const Rigid3d &rigid3d)
geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d &vector3d)
Rigid3< double > Rigid3d
void HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
cartographer::common::Mutex mutex_
std::unordered_map< int, TrajectoryState > GetTrajectoryStates() EXCLUDES(mutex_)
std::unique_ptr< MapBuilderInterface > map_builder_
std::unordered_map< std::string, int > landmark_to_index_
SensorBridge * sensor_bridge(int trajectory_id)
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
visualization_msgs::MarkerArray GetLandmarkPosesList()
void FinishTrajectory(int trajectory_id)
FloatColor GetColor(int id)
std::array< float, 3 > FloatColor
const TfBridge & tf_bridge() const
cartographer_ros_msgs::SubmapList GetSubmapList()
void LoadState(const std::string &state_filename, bool load_frozen_state)
std::unique_ptr<::cartographer::transform::Rigid3d > LookupToTracking(::cartographer::common::Time time, const std::string &frame_id) const
Definition: tf_bridge.cc:31
int AddTrajectory(const std::set< ::cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
bool SerializeState(const std::string &filename)
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder_
void move(std::vector< T > &a, std::vector< T > &b)
std::unordered_map< int, TrajectoryOptions > trajectory_options_
static Time now()
void OnLocalSlamResult(const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose, ::cartographer::sensor::RangeData range_data_in_local, const std::unique_ptr< const ::cartographer::mapping::TrajectoryBuilderInterface::InsertionResult > insertion_result) EXCLUDES(mutex_)
Mutex::Locker MutexLocker
MapBuilderBridge(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
std::unordered_map< int, std::unique_ptr< SensorBridge > > sensor_bridges_


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05