local_trajectory_builder_3d.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_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_
19 
20 #include <chrono>
21 #include <memory>
22 
30 #include "cartographer/mapping/proto/3d/local_trajectory_builder_options_3d.pb.h"
37 
38 namespace cartographer {
39 namespace mapping {
40 
41 // Wires up the local SLAM stack (i.e. pose extrapolator, scan matching, etc.)
42 // without loop closure.
44  public:
45  struct InsertionResult {
46  std::shared_ptr<const mapping::TrajectoryNode::Data> constant_data;
47  std::vector<std::shared_ptr<const mapping::Submap3D>> insertion_submaps;
48  };
49  struct MatchingResult {
53  // 'nullptr' if dropped by the motion filter.
54  std::unique_ptr<const InsertionResult> insertion_result;
55  };
56 
57  explicit LocalTrajectoryBuilder3D(
58  const mapping::proto::LocalTrajectoryBuilderOptions3D& options,
59  const std::vector<std::string>& expected_range_sensor_ids);
61 
64 
65  void AddImuData(const sensor::ImuData& imu_data);
66  // Returns 'MatchingResult' when range data accumulation completed,
67  // otherwise 'nullptr'. `TimedPointCloudData::time` is when the last point in
68  // `range_data` was acquired, `TimedPointCloudData::ranges` contains the
69  // relative time of point with respect to `TimedPointCloudData::time`.
70  std::unique_ptr<MatchingResult> AddRangeData(
71  const std::string& sensor_id,
72  const sensor::TimedPointCloudData& range_data);
73  void AddOdometryData(const sensor::OdometryData& odometry_data);
74 
75  static void RegisterMetrics(metrics::FamilyFactory* family_factory);
76 
77  private:
78  std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
80  const sensor::RangeData& filtered_range_data_in_tracking);
81 
82  std::unique_ptr<InsertionResult> InsertIntoSubmap(
83  common::Time time, const sensor::RangeData& filtered_range_data_in_local,
84  const sensor::RangeData& filtered_range_data_in_tracking,
85  const sensor::PointCloud& high_resolution_point_cloud_in_tracking,
86  const sensor::PointCloud& low_resolution_point_cloud_in_tracking,
87  const transform::Rigid3d& pose_estimate,
88  const Eigen::Quaterniond& gravity_alignment);
89 
90  const mapping::proto::LocalTrajectoryBuilderOptions3D options_;
92 
94  std::unique_ptr<scan_matching::RealTimeCorrelativeScanMatcher3D>
96  std::unique_ptr<scan_matching::CeresScanMatcher3D> ceres_scan_matcher_;
97 
98  std::unique_ptr<mapping::PoseExtrapolator> extrapolator_;
99 
102  std::chrono::steady_clock::time_point accumulation_started_;
103 
105 };
106 
107 } // namespace mapping
108 } // namespace cartographer
109 
110 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_
void AddOdometryData(const sensor::OdometryData &odometry_data)
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
static time_point time
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
LocalTrajectoryBuilder3D & operator=(const LocalTrajectoryBuilder3D &)=delete
std::unique_ptr< InsertionResult > InsertIntoSubmap(common::Time time, const sensor::RangeData &filtered_range_data_in_local, const sensor::RangeData &filtered_range_data_in_tracking, const sensor::PointCloud &high_resolution_point_cloud_in_tracking, const sensor::PointCloud &low_resolution_point_cloud_in_tracking, const transform::Rigid3d &pose_estimate, const Eigen::Quaterniond &gravity_alignment)
std::unique_ptr< MatchingResult > AddAccumulatedRangeData(common::Time time, const sensor::RangeData &filtered_range_data_in_tracking)
std::unique_ptr< scan_matching::CeresScanMatcher3D > ceres_scan_matcher_
std::chrono::steady_clock::time_point accumulation_started_
const mapping::proto::LocalTrajectoryBuilderOptions3D options_
LocalTrajectoryBuilder3D(const mapping::proto::LocalTrajectoryBuilderOptions3D &options, const std::vector< std::string > &expected_range_sensor_ids)
std::unique_ptr< scan_matching::RealTimeCorrelativeScanMatcher3D > real_time_correlative_scan_matcher_
std::unique_ptr< mapping::PoseExtrapolator > extrapolator_
std::shared_ptr< const mapping::TrajectoryNode::Data > constant_data
std::vector< std::shared_ptr< const mapping::Submap3D > > insertion_submaps


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58