trajectory_builder.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_H_
18 #define CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_H_
19 
20 #include <functional>
21 #include <memory>
22 #include <string>
23 
28 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
33 
34 namespace cartographer {
35 namespace mapping {
36 
37 proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(
38  common::LuaParameterDictionary* const parameter_dictionary);
39 
40 // This interface is used for both 2D and 3D SLAM.
42  public:
43  // Represents a newly computed pose. 'pose' is the end-user visualization of
44  // orientation and 'point_cloud' is the point cloud, in the local map frame.
45  struct PoseEstimate {
46  PoseEstimate() = default;
49  : time(time), pose(pose), point_cloud(point_cloud) {}
50 
51  common::Time time = common::Time::min();
54  };
55 
56  struct SubmapData {
57  const Submap* submap;
59  };
60 
62  virtual ~TrajectoryBuilder() {}
63 
64  TrajectoryBuilder(const TrajectoryBuilder&) = delete;
66 
67  virtual int num_submaps() = 0;
68  virtual SubmapData GetSubmapData(int submap_index) = 0;
69  virtual const PoseEstimate& pose_estimate() const = 0;
70 
71  virtual void AddSensorData(const string& sensor_id,
72  std::unique_ptr<sensor::Data> data) = 0;
73 
74  void AddRangefinderData(const string& sensor_id, common::Time time,
75  const Eigen::Vector3f& origin,
76  const sensor::PointCloud& ranges) {
77  AddSensorData(sensor_id,
78  common::make_unique<sensor::Data>(
79  time, sensor::Data::Rangefinder{origin, ranges}));
80  }
81 
82  void AddImuData(const string& sensor_id, common::Time time,
83  const Eigen::Vector3d& linear_acceleration,
84  const Eigen::Vector3d& angular_velocity) {
85  AddSensorData(sensor_id, common::make_unique<sensor::Data>(
86  time, sensor::Data::Imu{linear_acceleration,
87  angular_velocity}));
88  }
89 
90  void AddOdometerData(const string& sensor_id, common::Time time,
91  const transform::Rigid3d& odometer_pose) {
92  AddSensorData(sensor_id,
93  common::make_unique<sensor::Data>(time, odometer_pose));
94  }
95 };
96 
97 } // namespace mapping
98 } // namespace cartographer
99 
100 #endif // CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_H_
void AddRangefinderData(const string &sensor_id, common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges)
PoseEstimate(common::Time time, const transform::Rigid3d &pose, const sensor::PointCloud &point_cloud)
TrajectoryBuilder & operator=(const TrajectoryBuilder &)=delete
void AddImuData(const string &sensor_id, common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
void AddOdometerData(const string &sensor_id, common::Time time, const transform::Rigid3d &odometer_pose)
virtual const PoseEstimate & pose_estimate() const =0
proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
virtual SubmapData GetSubmapData(int submap_index)=0
virtual void AddSensorData(const string &sensor_id, std::unique_ptr< sensor::Data > data)=0


cartographer
Author(s):
autogenerated on Mon Jun 10 2019 12:51:39