local_trajectory_builder_2d.cc
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 
18 
19 #include <limits>
20 #include <memory>
21 
25 
26 namespace cartographer {
27 namespace mapping {
28 
35 
37  const proto::LocalTrajectoryBuilderOptions2D& options,
38  const std::vector<std::string>& expected_range_sensor_ids)
39  : options_(options),
40  active_submaps_(options.submaps_options()),
41  motion_filter_(options_.motion_filter_options()),
43  options_.real_time_correlative_scan_matcher_options()),
44  ceres_scan_matcher_(options_.ceres_scan_matcher_options()),
45  range_data_collator_(expected_range_sensor_ids) {}
46 
48 
51  const transform::Rigid3f& transform_to_gravity_aligned_frame,
52  const sensor::RangeData& range_data) const {
53  const sensor::RangeData cropped =
55  range_data, transform_to_gravity_aligned_frame),
56  options_.min_z(), options_.max_z());
57  return sensor::RangeData{
58  cropped.origin,
59  sensor::VoxelFilter(options_.voxel_filter_size()).Filter(cropped.returns),
60  sensor::VoxelFilter(options_.voxel_filter_size()).Filter(cropped.misses)};
61 }
62 
63 std::unique_ptr<transform::Rigid2d> LocalTrajectoryBuilder2D::ScanMatch(
64  const common::Time time, const transform::Rigid2d& pose_prediction,
65  const sensor::RangeData& gravity_aligned_range_data) {
66  std::shared_ptr<const Submap2D> matching_submap =
67  active_submaps_.submaps().front();
68  // The online correlative scan matcher will refine the initial estimate for
69  // the Ceres scan matcher.
70  transform::Rigid2d initial_ceres_pose = pose_prediction;
71  sensor::AdaptiveVoxelFilter adaptive_voxel_filter(
72  options_.adaptive_voxel_filter_options());
73  const sensor::PointCloud filtered_gravity_aligned_point_cloud =
74  adaptive_voxel_filter.Filter(gravity_aligned_range_data.returns);
75  if (filtered_gravity_aligned_point_cloud.empty()) {
76  return nullptr;
77  }
78  if (options_.use_online_correlative_scan_matching()) {
79  CHECK_EQ(options_.submaps_options().grid_options_2d().grid_type(),
80  proto::GridOptions2D_GridType_PROBABILITY_GRID);
82  pose_prediction, filtered_gravity_aligned_point_cloud,
83  *static_cast<const ProbabilityGrid*>(matching_submap->grid()),
84  &initial_ceres_pose);
86  }
87 
88  auto pose_observation = common::make_unique<transform::Rigid2d>();
89  ceres::Solver::Summary summary;
90  ceres_scan_matcher_.Match(pose_prediction.translation(), initial_ceres_pose,
91  filtered_gravity_aligned_point_cloud,
92  *matching_submap->grid(), pose_observation.get(),
93  &summary);
94  if (pose_observation) {
95  kCeresScanMatcherCostMetric->Observe(summary.final_cost);
96  double residual_distance =
97  (pose_observation->translation() - pose_prediction.translation())
98  .norm();
99  kScanMatcherResidualDistanceMetric->Observe(residual_distance);
100  double residual_angle = std::abs(pose_observation->rotation().angle() -
101  pose_prediction.rotation().angle());
102  kScanMatcherResidualAngleMetric->Observe(residual_angle);
103  }
104  return pose_observation;
105 }
106 
107 std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
109  const std::string& sensor_id,
110  const sensor::TimedPointCloudData& unsynchronized_data) {
111  auto synchronized_data =
112  range_data_collator_.AddRangeData(sensor_id, unsynchronized_data);
113  if (synchronized_data.ranges.empty()) {
114  LOG(INFO) << "Range data collator filling buffer.";
115  return nullptr;
116  }
117 
118  const common::Time& time = synchronized_data.time;
119  // Initialize extrapolator now if we do not ever use an IMU.
120  if (!options_.use_imu_data()) {
122  }
123 
124  if (extrapolator_ == nullptr) {
125  // Until we've initialized the extrapolator with our first IMU message, we
126  // cannot compute the orientation of the rangefinder.
127  LOG(INFO) << "Extrapolator not yet initialized.";
128  return nullptr;
129  }
130 
131  CHECK(!synchronized_data.ranges.empty());
132  // TODO(gaschler): Check if this can strictly be 0.
133  CHECK_LE(synchronized_data.ranges.back().point_time[3], 0.f);
134  const common::Time time_first_point =
135  time +
136  common::FromSeconds(synchronized_data.ranges.front().point_time[3]);
137  if (time_first_point < extrapolator_->GetLastPoseTime()) {
138  LOG(INFO) << "Extrapolator is still initializing.";
139  return nullptr;
140  }
141 
142  if (num_accumulated_ == 0) {
143  accumulation_started_ = std::chrono::steady_clock::now();
144  }
145 
146  std::vector<transform::Rigid3f> range_data_poses;
147  range_data_poses.reserve(synchronized_data.ranges.size());
148  bool warned = false;
149  for (const auto& range : synchronized_data.ranges) {
150  common::Time time_point = time + common::FromSeconds(range.point_time[3]);
151  if (time_point < extrapolator_->GetLastExtrapolatedTime()) {
152  if (!warned) {
153  LOG(ERROR)
154  << "Timestamp of individual range data point jumps backwards from "
155  << extrapolator_->GetLastExtrapolatedTime() << " to " << time_point;
156  warned = true;
157  }
158  time_point = extrapolator_->GetLastExtrapolatedTime();
159  }
160  range_data_poses.push_back(
161  extrapolator_->ExtrapolatePose(time_point).cast<float>());
162  }
163 
164  if (num_accumulated_ == 0) {
165  // 'accumulated_range_data_.origin' is uninitialized until the last
166  // accumulation.
168  }
169 
170  // Drop any returns below the minimum range and convert returns beyond the
171  // maximum range into misses.
172  for (size_t i = 0; i < synchronized_data.ranges.size(); ++i) {
173  const Eigen::Vector4f& hit = synchronized_data.ranges[i].point_time;
174  const Eigen::Vector3f origin_in_local =
175  range_data_poses[i] *
176  synchronized_data.origins.at(synchronized_data.ranges[i].origin_index);
177  const Eigen::Vector3f hit_in_local = range_data_poses[i] * hit.head<3>();
178  const Eigen::Vector3f delta = hit_in_local - origin_in_local;
179  const float range = delta.norm();
180  if (range >= options_.min_range()) {
181  if (range <= options_.max_range()) {
182  accumulated_range_data_.returns.push_back(hit_in_local);
183  } else {
185  origin_in_local +
186  options_.missing_data_ray_length() / range * delta);
187  }
188  }
189  }
191 
192  if (num_accumulated_ >= options_.num_accumulated_range_data()) {
193  num_accumulated_ = 0;
194  const transform::Rigid3d gravity_alignment = transform::Rigid3d::Rotation(
195  extrapolator_->EstimateGravityOrientation(time));
196  // TODO(gaschler): This assumes that 'range_data_poses.back()' is at time
197  // 'time'.
198  accumulated_range_data_.origin = range_data_poses.back().translation();
200  time,
202  gravity_alignment.cast<float>() * range_data_poses.back().inverse(),
204  gravity_alignment);
205  }
206  return nullptr;
207 }
208 
209 std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
211  const common::Time time,
212  const sensor::RangeData& gravity_aligned_range_data,
213  const transform::Rigid3d& gravity_alignment) {
214  if (gravity_aligned_range_data.returns.empty()) {
215  LOG(WARNING) << "Dropped empty horizontal range data.";
216  return nullptr;
217  }
218 
219  // Computes a gravity aligned pose prediction.
220  const transform::Rigid3d non_gravity_aligned_pose_prediction =
221  extrapolator_->ExtrapolatePose(time);
222  const transform::Rigid2d pose_prediction = transform::Project2D(
223  non_gravity_aligned_pose_prediction * gravity_alignment.inverse());
224 
225  // local map frame <- gravity-aligned frame
226  std::unique_ptr<transform::Rigid2d> pose_estimate_2d =
227  ScanMatch(time, pose_prediction, gravity_aligned_range_data);
228  if (pose_estimate_2d == nullptr) {
229  LOG(WARNING) << "Scan matching failed.";
230  return nullptr;
231  }
232  const transform::Rigid3d pose_estimate =
233  transform::Embed3D(*pose_estimate_2d) * gravity_alignment;
234  extrapolator_->AddPose(time, pose_estimate);
235 
236  sensor::RangeData range_data_in_local =
237  TransformRangeData(gravity_aligned_range_data,
238  transform::Embed3D(pose_estimate_2d->cast<float>()));
239  std::unique_ptr<InsertionResult> insertion_result =
240  InsertIntoSubmap(time, range_data_in_local, gravity_aligned_range_data,
241  pose_estimate, gravity_alignment.rotation());
242  auto duration = std::chrono::steady_clock::now() - accumulation_started_;
244  std::chrono::duration_cast<std::chrono::seconds>(duration).count());
245  return common::make_unique<MatchingResult>(
246  MatchingResult{time, pose_estimate, std::move(range_data_in_local),
247  std::move(insertion_result)});
248 }
249 
250 std::unique_ptr<LocalTrajectoryBuilder2D::InsertionResult>
252  const common::Time time, const sensor::RangeData& range_data_in_local,
253  const sensor::RangeData& gravity_aligned_range_data,
254  const transform::Rigid3d& pose_estimate,
255  const Eigen::Quaterniond& gravity_alignment) {
256  if (motion_filter_.IsSimilar(time, pose_estimate)) {
257  return nullptr;
258  }
259 
260  // Querying the active submaps must be done here before calling
261  // InsertRangeData() since the queried values are valid for next insertion.
262  std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;
263  for (const std::shared_ptr<Submap2D>& submap : active_submaps_.submaps()) {
264  insertion_submaps.push_back(submap);
265  }
266  active_submaps_.InsertRangeData(range_data_in_local);
267 
268  sensor::AdaptiveVoxelFilter adaptive_voxel_filter(
269  options_.loop_closure_adaptive_voxel_filter_options());
270  const sensor::PointCloud filtered_gravity_aligned_point_cloud =
271  adaptive_voxel_filter.Filter(gravity_aligned_range_data.returns);
272 
273  return common::make_unique<InsertionResult>(InsertionResult{
274  std::make_shared<const TrajectoryNode::Data>(TrajectoryNode::Data{
275  time,
276  gravity_alignment,
277  filtered_gravity_aligned_point_cloud,
278  {}, // 'high_resolution_point_cloud' is only used in 3D.
279  {}, // 'low_resolution_point_cloud' is only used in 3D.
280  {}, // 'rotational_scan_matcher_histogram' is only used in 3D.
281  pose_estimate}),
282  std::move(insertion_submaps)});
283 }
284 
286  CHECK(options_.use_imu_data()) << "An unexpected IMU packet was added.";
287  InitializeExtrapolator(imu_data.time);
288  extrapolator_->AddImuData(imu_data);
289 }
290 
292  const sensor::OdometryData& odometry_data) {
293  if (extrapolator_ == nullptr) {
294  // Until we've initialized the extrapolator we cannot add odometry data.
295  LOG(INFO) << "Extrapolator not yet initialized.";
296  return;
297  }
298  extrapolator_->AddOdometryData(odometry_data);
299 }
300 
302  if (extrapolator_ != nullptr) {
303  return;
304  }
305  // We derive velocities from poses which are at least 1 ms apart for numerical
306  // stability. Usually poses known to the extrapolator will be further apart
307  // in time and thus the last two are used.
308  constexpr double kExtrapolationEstimationTimeSec = 0.001;
309  // TODO(gaschler): Consider using InitializeWithImu as 3D does.
310  extrapolator_ = common::make_unique<PoseExtrapolator>(
311  ::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
312  options_.imu_gravity_time_constant());
314 }
315 
317  metrics::FamilyFactory* family_factory) {
318  auto* latency = family_factory->NewGaugeFamily(
319  "mapping_internal_2d_local_trajectory_builder_latency",
320  "Duration from first incoming point cloud in accumulation to local slam "
321  "result");
322  kLocalSlamLatencyMetric = latency->Add({});
323  auto score_boundaries = metrics::Histogram::FixedWidth(0.05, 20);
324  auto* scores = family_factory->NewHistogramFamily(
325  "mapping_internal_2d_local_trajectory_builder_scores",
326  "Local scan matcher scores", score_boundaries);
328  scores->Add({{"scan_matcher", "fast_correlative"}});
329  auto cost_boundaries = metrics::Histogram::ScaledPowersOf(2, 0.01, 100);
330  auto* costs = family_factory->NewHistogramFamily(
331  "mapping_internal_2d_local_trajectory_builder_costs",
332  "Local scan matcher costs", cost_boundaries);
333  kCeresScanMatcherCostMetric = costs->Add({{"scan_matcher", "ceres"}});
334  auto distance_boundaries = metrics::Histogram::ScaledPowersOf(2, 0.01, 10);
335  auto* residuals = family_factory->NewHistogramFamily(
336  "mapping_internal_2d_local_trajectory_builder_residuals",
337  "Local scan matcher residuals", distance_boundaries);
339  residuals->Add({{"component", "distance"}});
340  kScanMatcherResidualAngleMetric = residuals->Add({{"component", "angle"}});
341 }
342 
343 } // namespace mapping
344 } // namespace cartographer
void AddOdometryData(const sensor::OdometryData &odometry_data)
PointCloud Filter(const PointCloud &point_cloud) const
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)
static Rigid3 Rotation(const AngleAxis &angle_axis)
sensor::RangeData TransformToGravityAlignedFrameAndFilter(const transform::Rigid3f &transform_to_gravity_aligned_frame, const sensor::RangeData &range_data) const
virtual Family< Gauge > * NewGaugeFamily(const std::string &name, const std::string &description)=0
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
std::vector< std::shared_ptr< Submap2D > > submaps() const
Definition: submap_2d.cc:137
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
std::unique_ptr< ActiveSubmaps2D > active_submaps_
scan_matching::RealTimeCorrelativeScanMatcher2D real_time_correlative_scan_matcher_
Rigid3< T > Embed3D(const Rigid2< T > &transform)
Definition: transform.h:110
void InsertRangeData(const sensor::RangeData &range_data)
Definition: submap_2d.cc:143
Rigid3< OtherType > cast() const
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
const proto::LocalTrajectoryBuilderOptions2D options_
virtual Family< Histogram > * NewHistogramFamily(const std::string &name, const std::string &description, const Histogram::BucketBoundaries &boundaries)=0
RangeData TransformRangeData(const RangeData &range_data, const transform::Rigid3f &transform)
Definition: range_data.cc:25
Rigid2< T > Project2D(const Rigid3< T > &transform)
Definition: transform.h:103
const Quaternion & rotation() const
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
Duration FromSeconds(const double seconds)
Definition: time.cc:24
proto::ProbabilityGridRangeDataInserterOptions2D options_
static BucketBoundaries FixedWidth(double width, int num_finite_buckets)
int count
Definition: submap_3d.cc:33
std::unique_ptr< MatchingResult > AddAccumulatedRangeData(common::Time time, const sensor::RangeData &gravity_aligned_range_data, const transform::Rigid3d &gravity_alignment)
static auto * kFastCorrelativeScanMatcherScoreMetric
static auto * kScanMatcherResidualDistanceMetric
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
bool IsSimilar(common::Time time, const transform::Rigid3d &pose)
const Vector & translation() const
std::unique_ptr< RealTimeCorrelativeScanMatcher2D > real_time_correlative_scan_matcher_
double Match(const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const ProbabilityGrid &probability_grid, transform::Rigid2d *pose_estimate) const
RangeData CropRangeData(const RangeData &range_data, const float min_z, const float max_z)
Definition: range_data.cc:43
void Match(const Eigen::Vector2d &target_translation, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const Grid2D &grid, transform::Rigid2d *pose_estimate, ceres::Solver::Summary *summary) const
static BucketBoundaries ScaledPowersOf(double base, double scale_factor, double max_value)
sensor::TimedPointCloudOriginData AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &timed_point_cloud_data)
static Gauge * Null()
Definition: gauge.cc:36
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