local_trajectory_builder_2d.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_2D_LOCAL_TRAJECTORY_BUILDER_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_LOCAL_TRAJECTORY_BUILDER_2D_H_
19 
20 #include <chrono>
21 #include <memory>
22 
30 #include "cartographer/mapping/proto/2d/local_trajectory_builder_options_2d.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.
43 // TODO(gaschler): Add test for this class similar to the 3D test.
45  public:
46  struct InsertionResult {
47  std::shared_ptr<const TrajectoryNode::Data> constant_data;
48  std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;
49  };
50  struct MatchingResult {
54  // 'nullptr' if dropped by the motion filter.
55  std::unique_ptr<const InsertionResult> insertion_result;
56  };
57 
58  explicit LocalTrajectoryBuilder2D(
59  const proto::LocalTrajectoryBuilderOptions2D& options,
60  const std::vector<std::string>& expected_range_sensor_ids);
62 
65 
66  // Returns 'MatchingResult' when range data accumulation completed,
67  // otherwise 'nullptr'. Range data must be approximately horizontal
68  // for 2D SLAM. `TimedPointCloudData::time` is when the last point in
69  // `range_data` was acquired, `TimedPointCloudData::ranges` contains the
70  // relative time of point with respect to `TimedPointCloudData::time`.
71  std::unique_ptr<MatchingResult> AddRangeData(
72  const std::string& sensor_id,
73  const sensor::TimedPointCloudData& range_data);
74  void AddImuData(const sensor::ImuData& imu_data);
75  void AddOdometryData(const sensor::OdometryData& odometry_data);
76 
77  static void RegisterMetrics(metrics::FamilyFactory* family_factory);
78 
79  private:
80  std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
81  common::Time time, const sensor::RangeData& gravity_aligned_range_data,
82  const transform::Rigid3d& gravity_alignment);
84  const transform::Rigid3f& transform_to_gravity_aligned_frame,
85  const sensor::RangeData& range_data) const;
86 
87  std::unique_ptr<InsertionResult> InsertIntoSubmap(
88  common::Time time, const sensor::RangeData& range_data_in_local,
89  const sensor::RangeData& gravity_aligned_range_data,
90  const transform::Rigid3d& pose_estimate,
91  const Eigen::Quaterniond& gravity_alignment);
92 
93  // Scan matches 'gravity_aligned_range_data' and returns the observed pose,
94  // or nullptr on failure.
95  std::unique_ptr<transform::Rigid2d> ScanMatch(
96  common::Time time, const transform::Rigid2d& pose_prediction,
97  const sensor::RangeData& gravity_aligned_range_data);
98 
99  // Lazily constructs a PoseExtrapolator.
101 
102  const proto::LocalTrajectoryBuilderOptions2D options_;
104 
109 
110  std::unique_ptr<PoseExtrapolator> extrapolator_;
111 
114  std::chrono::steady_clock::time_point accumulation_started_;
115 
117 };
118 
119 } // namespace mapping
120 } // namespace cartographer
121 
122 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_LOCAL_TRAJECTORY_BUILDER_2D_H_
void AddOdometryData(const sensor::OdometryData &odometry_data)
std::unique_ptr< InsertionResult > InsertIntoSubmap(common::Time time, const sensor::RangeData &range_data_in_local, const sensor::RangeData &gravity_aligned_range_data, const transform::Rigid3d &pose_estimate, const Eigen::Quaterniond &gravity_alignment)
sensor::RangeData TransformToGravityAlignedFrameAndFilter(const transform::Rigid3f &transform_to_gravity_aligned_frame, const sensor::RangeData &range_data) const
LocalTrajectoryBuilder2D & operator=(const LocalTrajectoryBuilder2D &)=delete
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
std::vector< std::shared_ptr< const Submap2D > > insertion_submaps
scan_matching::RealTimeCorrelativeScanMatcher2D real_time_correlative_scan_matcher_
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
const proto::LocalTrajectoryBuilderOptions2D options_
LocalTrajectoryBuilder2D(const proto::LocalTrajectoryBuilderOptions2D &options, const std::vector< std::string > &expected_range_sensor_ids)
std::chrono::steady_clock::time_point accumulation_started_
static time_point time
std::unique_ptr< MatchingResult > AddAccumulatedRangeData(common::Time time, const sensor::RangeData &gravity_aligned_range_data, const transform::Rigid3d &gravity_alignment)
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
std::unique_ptr< transform::Rigid2d > ScanMatch(common::Time time, const transform::Rigid2d &pose_prediction, const sensor::RangeData &gravity_aligned_range_data)


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