mapping_3d/global_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_3D_GLOBAL_TRAJECTORY_BUILDER_H_
18 #define CARTOGRAPHER_MAPPING_3D_GLOBAL_TRAJECTORY_BUILDER_H_
19 
20 #include <memory>
21 
24 #include "cartographer/mapping_3d/proto/local_trajectory_builder_options.pb.h"
26 
27 namespace cartographer {
28 namespace mapping_3d {
29 
32  public:
33  GlobalTrajectoryBuilder(const proto::LocalTrajectoryBuilderOptions& options,
34  int trajectory_id,
35  mapping_3d::SparsePoseGraph* sparse_pose_graph);
36  ~GlobalTrajectoryBuilder() override;
37 
40 
41  int num_submaps() override;
42  SubmapData GetSubmapData(int submap_index) override;
43  void AddImuData(common::Time time, const Eigen::Vector3d& linear_acceleration,
44  const Eigen::Vector3d& angular_velocity) override;
45  void AddRangefinderData(common::Time time, const Eigen::Vector3f& origin,
46  const sensor::PointCloud& ranges) override;
47  void AddOdometerData(common::Time time,
48  const transform::Rigid3d& pose) override;
49  const PoseEstimate& pose_estimate() const override;
50 
51  private:
52  const int trajectory_id_;
54  std::unique_ptr<LocalTrajectoryBuilderInterface> local_trajectory_builder_;
55 };
56 
57 } // namespace mapping_3d
58 } // namespace cartographer
59 
60 #endif // CARTOGRAPHER_MAPPING_3D_GLOBAL_TRAJECTORY_BUILDER_H_
void AddImuData(common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity) override
GlobalTrajectoryBuilder(const proto::LocalTrajectoryBuilderOptions &options, int trajectory_id, mapping_3d::SparsePoseGraph *sparse_pose_graph)
void AddRangefinderData(common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges) override
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
transform::Rigid3d pose
GlobalTrajectoryBuilder & operator=(const GlobalTrajectoryBuilder &)=delete
std::unique_ptr< LocalTrajectoryBuilderInterface > local_trajectory_builder_
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
void AddOdometerData(common::Time time, const transform::Rigid3d &pose) override


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