trajectory_builder_interface.h
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 
17 #ifndef CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_
18 #define CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_
19 
20 #include <functional>
21 #include <memory>
22 #include <string>
23 
28 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
35 
36 namespace cartographer {
37 namespace mapping {
38 
39 proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(
40  common::LuaParameterDictionary* const parameter_dictionary);
41 
42 class LocalSlamResultData;
43 
44 // This interface is used for both 2D and 3D SLAM. Implementations wire up a
45 // global SLAM stack, i.e. local SLAM for initial pose estimates, scan matching
46 // to detect loop closure, and a sparse pose graph optimization to compute
47 // optimized pose estimates.
49  public:
50  struct InsertionResult {
52  std::shared_ptr<const TrajectoryNode::Data> constant_data;
53  std::vector<std::shared_ptr<const Submap>> insertion_submaps;
54  };
55 
56  // A callback which is called after local SLAM processes an accumulated
57  // 'sensor::RangeData'. If the data was inserted into a submap, reports the
58  // assigned 'NodeId', otherwise 'nullptr' if the data was filtered out.
60  std::function<void(int /* trajectory ID */, common::Time,
61  transform::Rigid3d /* local pose estimate */,
62  sensor::RangeData /* in local frame */,
63  std::unique_ptr<const InsertionResult>)>;
64 
65  struct SensorId {
66  enum class SensorType {
67  RANGE = 0,
68  IMU,
69  ODOMETRY,
71  LANDMARK,
73  };
74 
76  std::string id;
77 
78  bool operator==(const SensorId& other) const {
79  return std::forward_as_tuple(type, id) ==
80  std::forward_as_tuple(other.type, other.id);
81  }
82 
83  bool operator<(const SensorId& other) const {
84  return std::forward_as_tuple(type, id) <
85  std::forward_as_tuple(other.type, other.id);
86  }
87  };
88 
91 
94  delete;
95 
96  virtual void AddSensorData(
97  const std::string& sensor_id,
98  const sensor::TimedPointCloudData& timed_point_cloud_data) = 0;
99  virtual void AddSensorData(const std::string& sensor_id,
100  const sensor::ImuData& imu_data) = 0;
101  virtual void AddSensorData(const std::string& sensor_id,
102  const sensor::OdometryData& odometry_data) = 0;
103  virtual void AddSensorData(
104  const std::string& sensor_id,
105  const sensor::FixedFramePoseData& fixed_frame_pose) = 0;
106  virtual void AddSensorData(const std::string& sensor_id,
107  const sensor::LandmarkData& landmark_data) = 0;
108  // Allows to directly add local SLAM results to the 'PoseGraph'. Note that it
109  // is invalid to add local SLAM results for a trajectory that has a
110  // 'LocalTrajectoryBuilder2D/3D'.
111  virtual void AddLocalSlamResultData(
112  std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) = 0;
113 };
114 
117  const proto::SensorId& sensor_id_proto);
118 
119 } // namespace mapping
120 } // namespace cartographer
121 
122 #endif // CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_
PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
Definition: pose_graph.cc:38
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
TrajectoryBuilderInterface & operator=(const TrajectoryBuilderInterface &)=delete
proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
virtual void AddLocalSlamResultData(std::unique_ptr< mapping::LocalSlamResultData > local_slam_result_data)=0
proto::MapLimits ToProto(const MapLimits &map_limits)
Definition: map_limits.h:92
virtual void AddSensorData(const std::string &sensor_id, const sensor::TimedPointCloudData &timed_point_cloud_data)=0
::cartographer::mapping::TrajectoryBuilderInterface::SensorId SensorId
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58