kalman_local_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_KALMAN_LOCAL_TRAJECTORY_BUILDER_H_
18 #define CARTOGRAPHER_MAPPING_3D_KALMAN_LOCAL_TRAJECTORY_BUILDER_H_
19 
20 #include <memory>
21 
27 #include "cartographer/mapping_3d/proto/local_trajectory_builder_options.pb.h"
33 
34 namespace cartographer {
35 namespace mapping_3d {
36 
37 // Wires up the local SLAM stack (i.e. UKF, scan matching, etc.) without loop
38 // closure.
40  public:
42  const proto::LocalTrajectoryBuilderOptions& options);
44 
47  delete;
48 
49  void AddImuData(common::Time time, const Eigen::Vector3d& linear_acceleration,
50  const Eigen::Vector3d& angular_velocity) override;
51  std::unique_ptr<InsertionResult> AddRangefinderData(
52  common::Time time, const Eigen::Vector3f& origin,
53  const sensor::PointCloud& ranges) override;
54  void AddOdometerData(common::Time time,
55  const transform::Rigid3d& pose) override;
56  mapping_3d::Submaps* submaps() override;
57  const PoseEstimate& pose_estimate() const override;
58 
59  private:
60  std::unique_ptr<InsertionResult> AddAccumulatedRangeData(
61  common::Time time, const sensor::RangeData& range_data_in_tracking);
62 
63  std::unique_ptr<InsertionResult> InsertIntoSubmap(
64  common::Time time, const sensor::RangeData& range_data_in_tracking,
65  const transform::Rigid3d& pose_observation);
66 
67  const proto::LocalTrajectoryBuilderOptions options_;
68  std::unique_ptr<mapping_3d::Submaps> submaps_;
69 
71 
72  // Pose of the last computed scan match.
74 
76  std::unique_ptr<scan_matching::RealTimeCorrelativeScanMatcher>
78  std::unique_ptr<scan_matching::CeresScanMatcher> ceres_scan_matcher_;
79 
80  std::unique_ptr<kalman_filter::PoseTracker> pose_tracker_;
81 
85 };
86 
87 } // namespace mapping_3d
88 } // namespace cartographer
89 
90 #endif // CARTOGRAPHER_MAPPING_3D_KALMAN_LOCAL_TRAJECTORY_BUILDER_H_
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
std::unique_ptr< scan_matching::RealTimeCorrelativeScanMatcher > real_time_correlative_scan_matcher_
transform::Rigid3d pose
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
void AddImuData(common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity) override
std::unique_ptr< InsertionResult > InsertIntoSubmap(common::Time time, const sensor::RangeData &range_data_in_tracking, const transform::Rigid3d &pose_observation)
std::unique_ptr< InsertionResult > AddRangefinderData(common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges) override
std::unique_ptr< scan_matching::CeresScanMatcher > ceres_scan_matcher_
KalmanLocalTrajectoryBuilder & operator=(const KalmanLocalTrajectoryBuilder &)=delete
KalmanLocalTrajectoryBuilder(const proto::LocalTrajectoryBuilderOptions &options)
std::unique_ptr< InsertionResult > AddAccumulatedRangeData(common::Time time, const sensor::RangeData &range_data_in_tracking)
void AddOdometerData(common::Time time, const transform::Rigid3d &pose) override
std::unique_ptr< kalman_filter::PoseTracker > pose_tracker_


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