local_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_3D_LOCAL_TRAJECTORY_BUILDER_INTERFACE_H_
18 #define CARTOGRAPHER_MAPPING_3D_LOCAL_TRAJECTORY_BUILDER_INTERFACE_H_
19 
20 #include <memory>
21 #include <vector>
22 
28 
29 namespace cartographer {
30 namespace mapping_3d {
31 
33  public:
35 
36  struct InsertionResult {
41  std::vector<const Submap*> insertion_submaps;
42  };
43 
45 
47  delete;
49  const LocalTrajectoryBuilderInterface&) = delete;
50 
51  virtual void AddImuData(common::Time time,
52  const Eigen::Vector3d& linear_acceleration,
53  const Eigen::Vector3d& angular_velocity) = 0;
54  virtual std::unique_ptr<InsertionResult> AddRangefinderData(
55  common::Time time, const Eigen::Vector3f& origin,
56  const sensor::PointCloud& ranges) = 0;
57  virtual void AddOdometerData(common::Time time,
58  const transform::Rigid3d& pose) = 0;
59 
60  virtual mapping_3d::Submaps* submaps() = 0;
61  virtual const PoseEstimate& pose_estimate() const = 0;
62 
63  protected:
65 };
66 
67 } // namespace mapping_3d
68 } // namespace cartographer
69 
70 #endif // CARTOGRAPHER_MAPPING_3D_LOCAL_TRAJECTORY_BUILDER_INTERFACE_H_
virtual void AddImuData(common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)=0
virtual const PoseEstimate & pose_estimate() const =0
LocalTrajectoryBuilderInterface & operator=(const LocalTrajectoryBuilderInterface &)=delete
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
virtual std::unique_ptr< InsertionResult > AddRangefinderData(common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges)=0
transform::Rigid3d pose
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
virtual void AddOdometerData(common::Time time, const transform::Rigid3d &pose)=0


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