global_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_GLOBAL_TRAJECTORY_BUILDER_INTERFACE_H_
18 #define CARTOGRAPHER_MAPPING_GLOBAL_TRAJECTORY_BUILDER_INTERFACE_H_
19 
20 #include <functional>
21 #include <memory>
22 #include <string>
23 #include <vector>
24 
31 
32 namespace cartographer {
33 namespace mapping {
34 
35 // This interface is used for both 2D and 3D SLAM. Implementations wire up a
36 // global SLAM stack, i.e. local SLAM for initial pose estimates, scan matching
37 // to detect loop closure, and a sparse pose graph optimization to compute
38 // optimized pose estimates.
40  public:
43 
46 
48  delete;
50  const GlobalTrajectoryBuilderInterface&) = delete;
51 
52  virtual int num_submaps() = 0;
53  virtual SubmapData GetSubmapData(int submap_index) = 0;
54  virtual const PoseEstimate& pose_estimate() const = 0;
55 
57  const Eigen::Vector3f& origin,
58  const sensor::PointCloud& ranges) = 0;
59  virtual void AddImuData(common::Time time,
60  const Eigen::Vector3d& linear_acceleration,
61  const Eigen::Vector3d& angular_velocity) = 0;
62  virtual void AddOdometerData(common::Time time,
63  const transform::Rigid3d& pose) = 0;
64 };
65 
66 } // namespace mapping
67 } // namespace cartographer
68 
69 #endif // CARTOGRAPHER_MAPPING_GLOBAL_TRAJECTORY_BUILDER_INTERFACE_H_
virtual SubmapData GetSubmapData(int submap_index)=0
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
transform::Rigid3d pose
virtual const PoseEstimate & pose_estimate() const =0
virtual void AddOdometerData(common::Time time, const transform::Rigid3d &pose)=0
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
GlobalTrajectoryBuilderInterface & operator=(const GlobalTrajectoryBuilderInterface &)=delete
virtual void AddRangefinderData(common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges)=0
virtual void AddImuData(common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)=0


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