mapping_2d/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_2D_GLOBAL_TRAJECTORY_BUILDER_H_
18 #define CARTOGRAPHER_MAPPING_2D_GLOBAL_TRAJECTORY_BUILDER_H_
19 
23 
24 namespace cartographer {
25 namespace mapping_2d {
26 
29  public:
30  GlobalTrajectoryBuilder(const proto::LocalTrajectoryBuilderOptions& options,
31  int trajectory_id,
32  SparsePoseGraph* sparse_pose_graph);
33  ~GlobalTrajectoryBuilder() override;
34 
37 
38  int num_submaps() override;
39  SubmapData GetSubmapData(int submap_index) override;
41  const override;
42 
43  // Projects 'ranges' into 2D. Therefore, 'ranges' should be approximately
44  // parallel to the ground plane.
45  void AddRangefinderData(common::Time time, const Eigen::Vector3f& origin,
46  const sensor::PointCloud& ranges) override;
47  void AddImuData(common::Time time, const Eigen::Vector3d& linear_acceleration,
48  const Eigen::Vector3d& angular_velocity) override;
49  void AddOdometerData(common::Time time,
50  const transform::Rigid3d& pose) override;
51 
52  private:
53  const int trajectory_id_;
56 };
57 
58 } // namespace mapping_2d
59 } // namespace cartographer
60 
61 #endif // CARTOGRAPHER_MAPPING_2D_GLOBAL_TRAJECTORY_BUILDER_H_
GlobalTrajectoryBuilder(const proto::LocalTrajectoryBuilderOptions &options, int trajectory_id, SparsePoseGraph *sparse_pose_graph)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
GlobalTrajectoryBuilder & operator=(const GlobalTrajectoryBuilder &)=delete
transform::Rigid3d pose
void AddOdometerData(common::Time time, const transform::Rigid3d &pose) override
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
void AddRangefinderData(common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges) override
const mapping::GlobalTrajectoryBuilderInterface::PoseEstimate & pose_estimate() const override
void AddImuData(common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity) override


cartographer
Author(s):
autogenerated on Wed Jun 5 2019 21:57:58