local_trajectory_builder_3d.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 <memory>
20 
24 #include "cartographer/mapping/proto/3d/local_trajectory_builder_options_3d.pb.h"
25 #include "cartographer/mapping/proto/3d/submaps_options_3d.pb.h"
26 #include "cartographer/mapping/proto/scan_matching//ceres_scan_matcher_options_3d.pb.h"
27 #include "cartographer/mapping/proto/scan_matching//real_time_correlative_scan_matcher_options.pb.h"
28 #include "glog/logging.h"
29 
30 namespace cartographer {
31 namespace mapping {
32 
39 
41  const mapping::proto::LocalTrajectoryBuilderOptions3D& options,
42  const std::vector<std::string>& expected_range_sensor_ids)
43  : options_(options),
44  active_submaps_(options.submaps_options()),
45  motion_filter_(options.motion_filter_options()),
47  common::make_unique<scan_matching::RealTimeCorrelativeScanMatcher3D>(
48  options_.real_time_correlative_scan_matcher_options())),
50  common::make_unique<scan_matching::CeresScanMatcher3D>(
51  options_.ceres_scan_matcher_options())),
52  accumulated_range_data_{Eigen::Vector3f::Zero(), {}, {}},
53  range_data_collator_(expected_range_sensor_ids) {}
54 
56 
58  if (extrapolator_ != nullptr) {
59  extrapolator_->AddImuData(imu_data);
60  return;
61  }
62  // We derive velocities from poses which are at least 1 ms apart for numerical
63  // stability. Usually poses known to the extrapolator will be further apart
64  // in time and thus the last two are used.
65  constexpr double kExtrapolationEstimationTimeSec = 0.001;
67  ::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
68  options_.imu_gravity_time_constant(), imu_data);
69 }
70 
71 std::unique_ptr<LocalTrajectoryBuilder3D::MatchingResult>
73  const std::string& sensor_id,
74  const sensor::TimedPointCloudData& unsynchronized_data) {
75  auto synchronized_data =
76  range_data_collator_.AddRangeData(sensor_id, unsynchronized_data);
77  if (synchronized_data.ranges.empty()) {
78  LOG(INFO) << "Range data collator filling buffer.";
79  return nullptr;
80  }
81 
82  const common::Time& time = synchronized_data.time;
83  if (extrapolator_ == nullptr) {
84  // Until we've initialized the extrapolator with our first IMU message, we
85  // cannot compute the orientation of the rangefinder.
86  LOG(INFO) << "IMU not yet initialized.";
87  return nullptr;
88  }
89 
90  CHECK(!synchronized_data.ranges.empty());
91  CHECK_LE(synchronized_data.ranges.back().point_time[3], 0.f);
92  const common::Time time_first_point =
93  time +
94  common::FromSeconds(synchronized_data.ranges.front().point_time[3]);
95  if (time_first_point < extrapolator_->GetLastPoseTime()) {
96  LOG(INFO) << "Extrapolator is still initializing.";
97  return nullptr;
98  }
99 
100  if (num_accumulated_ == 0) {
101  accumulation_started_ = std::chrono::steady_clock::now();
102  }
103 
104  std::vector<sensor::TimedPointCloudOriginData::RangeMeasurement> hits =
105  sensor::VoxelFilter(0.5f * options_.voxel_filter_size())
106  .Filter(synchronized_data.ranges);
107 
108  std::vector<transform::Rigid3f> hits_poses;
109  hits_poses.reserve(hits.size());
110  bool warned = false;
111  for (const auto& hit : hits) {
112  common::Time time_point = time + common::FromSeconds(hit.point_time[3]);
113  if (time_point < extrapolator_->GetLastExtrapolatedTime()) {
114  if (!warned) {
115  LOG(ERROR)
116  << "Timestamp of individual range data point jumps backwards from "
117  << extrapolator_->GetLastExtrapolatedTime() << " to " << time_point;
118  warned = true;
119  }
120  time_point = extrapolator_->GetLastExtrapolatedTime();
121  }
122  hits_poses.push_back(
123  extrapolator_->ExtrapolatePose(time_point).cast<float>());
124  }
125 
126  if (num_accumulated_ == 0) {
127  // 'accumulated_range_data_.origin' is not used.
129  }
130 
131  for (size_t i = 0; i < hits.size(); ++i) {
132  const Eigen::Vector3f hit_in_local =
133  hits_poses[i] * hits[i].point_time.head<3>();
134  const Eigen::Vector3f origin_in_local =
135  hits_poses[i] * synchronized_data.origins.at(hits[i].origin_index);
136  const Eigen::Vector3f delta = hit_in_local - origin_in_local;
137  const float range = delta.norm();
138  if (range >= options_.min_range()) {
139  if (range <= options_.max_range()) {
140  accumulated_range_data_.returns.push_back(hit_in_local);
141  } else {
142  // We insert a ray cropped to 'max_range' as a miss for hits beyond the
143  // maximum range. This way the free space up to the maximum range will
144  // be updated.
146  origin_in_local + options_.max_range() / range * delta);
147  }
148  }
149  }
151 
152  if (num_accumulated_ >= options_.num_accumulated_range_data()) {
153  num_accumulated_ = 0;
154  transform::Rigid3f current_pose =
155  extrapolator_->ExtrapolatePose(time).cast<float>();
156  const sensor::RangeData filtered_range_data = {
157  current_pose.translation(),
158  sensor::VoxelFilter(options_.voxel_filter_size())
160  sensor::VoxelFilter(options_.voxel_filter_size())
163  time, sensor::TransformRangeData(filtered_range_data,
164  current_pose.inverse()));
165  }
166  return nullptr;
167 }
168 
169 std::unique_ptr<LocalTrajectoryBuilder3D::MatchingResult>
171  const common::Time time,
172  const sensor::RangeData& filtered_range_data_in_tracking) {
173  if (filtered_range_data_in_tracking.returns.empty()) {
174  LOG(WARNING) << "Dropped empty range data.";
175  return nullptr;
176  }
177 
178  const transform::Rigid3d pose_prediction =
179  extrapolator_->ExtrapolatePose(time);
180 
181  std::shared_ptr<const mapping::Submap3D> matching_submap =
182  active_submaps_.submaps().front();
183  transform::Rigid3d initial_ceres_pose =
184  matching_submap->local_pose().inverse() * pose_prediction;
185  sensor::AdaptiveVoxelFilter adaptive_voxel_filter(
186  options_.high_resolution_adaptive_voxel_filter_options());
187  const sensor::PointCloud high_resolution_point_cloud_in_tracking =
188  adaptive_voxel_filter.Filter(filtered_range_data_in_tracking.returns);
189  if (high_resolution_point_cloud_in_tracking.empty()) {
190  LOG(WARNING) << "Dropped empty high resolution point cloud data.";
191  return nullptr;
192  }
193  if (options_.use_online_correlative_scan_matching()) {
194  // We take a copy since we use 'initial_ceres_pose' as an output argument.
195  const transform::Rigid3d initial_pose = initial_ceres_pose;
196  double score = real_time_correlative_scan_matcher_->Match(
197  initial_pose, high_resolution_point_cloud_in_tracking,
198  matching_submap->high_resolution_hybrid_grid(), &initial_ceres_pose);
200  }
201 
202  transform::Rigid3d pose_observation_in_submap;
203  ceres::Solver::Summary summary;
204 
205  sensor::AdaptiveVoxelFilter low_resolution_adaptive_voxel_filter(
206  options_.low_resolution_adaptive_voxel_filter_options());
207  const sensor::PointCloud low_resolution_point_cloud_in_tracking =
208  low_resolution_adaptive_voxel_filter.Filter(
209  filtered_range_data_in_tracking.returns);
210  if (low_resolution_point_cloud_in_tracking.empty()) {
211  LOG(WARNING) << "Dropped empty low resolution point cloud data.";
212  return nullptr;
213  }
214  ceres_scan_matcher_->Match(
215  (matching_submap->local_pose().inverse() * pose_prediction).translation(),
216  initial_ceres_pose,
217  {{&high_resolution_point_cloud_in_tracking,
218  &matching_submap->high_resolution_hybrid_grid()},
219  {&low_resolution_point_cloud_in_tracking,
220  &matching_submap->low_resolution_hybrid_grid()}},
221  &pose_observation_in_submap, &summary);
222  kCeresScanMatcherCostMetric->Observe(summary.final_cost);
223  double residual_distance = (pose_observation_in_submap.translation() -
224  initial_ceres_pose.translation())
225  .norm();
226  kScanMatcherResidualDistanceMetric->Observe(residual_distance);
227  double residual_angle = pose_observation_in_submap.rotation().angularDistance(
228  initial_ceres_pose.rotation());
229  kScanMatcherResidualAngleMetric->Observe(residual_angle);
230  const transform::Rigid3d pose_estimate =
231  matching_submap->local_pose() * pose_observation_in_submap;
232  extrapolator_->AddPose(time, pose_estimate);
233  const Eigen::Quaterniond gravity_alignment =
234  extrapolator_->EstimateGravityOrientation(time);
235 
236  sensor::RangeData filtered_range_data_in_local = sensor::TransformRangeData(
237  filtered_range_data_in_tracking, pose_estimate.cast<float>());
238  std::unique_ptr<InsertionResult> insertion_result = InsertIntoSubmap(
239  time, filtered_range_data_in_local, filtered_range_data_in_tracking,
240  high_resolution_point_cloud_in_tracking,
241  low_resolution_point_cloud_in_tracking, pose_estimate, gravity_alignment);
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>(MatchingResult{
246  time, pose_estimate, std::move(filtered_range_data_in_local),
247  std::move(insertion_result)});
248 }
249 
251  const sensor::OdometryData& odometry_data) {
252  if (extrapolator_ == nullptr) {
253  // Until we've initialized the extrapolator we cannot add odometry data.
254  LOG(INFO) << "Extrapolator not yet initialized.";
255  return;
256  }
257  extrapolator_->AddOdometryData(odometry_data);
258 }
259 
260 std::unique_ptr<LocalTrajectoryBuilder3D::InsertionResult>
262  const common::Time time,
263  const sensor::RangeData& filtered_range_data_in_local,
264  const sensor::RangeData& filtered_range_data_in_tracking,
265  const sensor::PointCloud& high_resolution_point_cloud_in_tracking,
266  const sensor::PointCloud& low_resolution_point_cloud_in_tracking,
267  const transform::Rigid3d& pose_estimate,
268  const Eigen::Quaterniond& gravity_alignment) {
269  if (motion_filter_.IsSimilar(time, pose_estimate)) {
270  return nullptr;
271  }
272  // Querying the active submaps must be done here before calling
273  // InsertRangeData() since the queried values are valid for next insertion.
274  std::vector<std::shared_ptr<const mapping::Submap3D>> insertion_submaps;
275  for (const std::shared_ptr<mapping::Submap3D>& submap :
277  insertion_submaps.push_back(submap);
278  }
279  active_submaps_.InsertRangeData(filtered_range_data_in_local,
280  gravity_alignment);
281  const Eigen::VectorXf rotational_scan_matcher_histogram =
284  filtered_range_data_in_tracking.returns,
285  transform::Rigid3f::Rotation(gravity_alignment.cast<float>())),
286  options_.rotational_histogram_size());
287  return common::make_unique<InsertionResult>(
288  InsertionResult{std::make_shared<const mapping::TrajectoryNode::Data>(
290  time,
291  gravity_alignment,
292  {}, // 'filtered_point_cloud' is only used in 2D.
293  high_resolution_point_cloud_in_tracking,
294  low_resolution_point_cloud_in_tracking,
295  rotational_scan_matcher_histogram,
296  pose_estimate}),
297  std::move(insertion_submaps)});
298 }
299 
301  metrics::FamilyFactory* family_factory) {
302  auto* latency = family_factory->NewGaugeFamily(
303  "mapping_internal_3d_local_trajectory_builder_latency",
304  "Duration from first incoming point cloud in accumulation to local slam "
305  "result");
306  kLocalSlamLatencyMetric = latency->Add({});
307  auto score_boundaries = metrics::Histogram::FixedWidth(0.05, 20);
308  auto* scores = family_factory->NewHistogramFamily(
309  "mapping_internal_3d_local_trajectory_builder_scores",
310  "Local scan matcher scores", score_boundaries);
312  scores->Add({{"scan_matcher", "real_time_correlative"}});
313  auto cost_boundaries = metrics::Histogram::ScaledPowersOf(2, 0.01, 100);
314  auto* costs = family_factory->NewHistogramFamily(
315  "mapping_internal_3d_local_trajectory_builder_costs",
316  "Local scan matcher costs", cost_boundaries);
317  kCeresScanMatcherCostMetric = costs->Add({{"scan_matcher", "ceres"}});
318  auto distance_boundaries = metrics::Histogram::ScaledPowersOf(2, 0.01, 10);
319  auto* residuals = family_factory->NewHistogramFamily(
320  "mapping_internal_3d_local_trajectory_builder_residuals",
321  "Local scan matcher residuals", distance_boundaries);
323  residuals->Add({{"component", "distance"}});
324  kScanMatcherResidualAngleMetric = residuals->Add({{"component", "angle"}});
325 }
326 
327 } // namespace mapping
328 } // namespace cartographer
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
Definition: point_cloud.cc:25
PointCloud Filter(const PointCloud &point_cloud) const
void AddOdometryData(const sensor::OdometryData &odometry_data)
static Rigid3 Rotation(const AngleAxis &angle_axis)
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
virtual Family< Gauge > * NewGaugeFamily(const std::string &name, const std::string &description)=0
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
std::unique_ptr< ActiveSubmaps2D > active_submaps_
Rigid3< OtherType > cast() const
static std::unique_ptr< PoseExtrapolator > InitializeWithImu(common::Duration pose_queue_duration, double imu_gravity_time_constant, const sensor::ImuData &imu_data)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
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
const Quaternion & rotation() const
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)
const Vector & translation() const
int count
Definition: submap_3d.cc:33
std::vector< std::shared_ptr< Submap3D > > submaps() const
Definition: submap_3d.cc:293
static auto * kScanMatcherResidualDistanceMetric
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
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_
static auto * kRealTimeCorrelativeScanMatcherScoreMetric
bool IsSimilar(common::Time time, const transform::Rigid3d &pose)
static Eigen::VectorXf ComputeHistogram(const sensor::PointCloud &point_cloud, int histogram_size)
std::chrono::steady_clock::time_point accumulation_started_
const mapping::proto::LocalTrajectoryBuilderOptions3D options_
std::unique_ptr< RealTimeCorrelativeScanMatcher2D > real_time_correlative_scan_matcher_
void InsertRangeData(const sensor::RangeData &range_data, const Eigen::Quaterniond &gravity_alignment)
Definition: submap_3d.cc:299
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_
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< mapping::PoseExtrapolator > extrapolator_


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