local_trajectory_builder_2d.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/mapping/internal/2d/local_trajectory_builder_2d.h"
00018 
00019 #include <limits>
00020 #include <memory>
00021 
00022 #include "absl/memory/memory.h"
00023 #include "cartographer/metrics/family_factory.h"
00024 #include "cartographer/sensor/range_data.h"
00025 
00026 namespace cartographer {
00027 namespace mapping {
00028 
00029 static auto* kLocalSlamLatencyMetric = metrics::Gauge::Null();
00030 static auto* kLocalSlamRealTimeRatio = metrics::Gauge::Null();
00031 static auto* kLocalSlamCpuRealTimeRatio = metrics::Gauge::Null();
00032 static auto* kRealTimeCorrelativeScanMatcherScoreMetric =
00033     metrics::Histogram::Null();
00034 static auto* kCeresScanMatcherCostMetric = metrics::Histogram::Null();
00035 static auto* kScanMatcherResidualDistanceMetric = metrics::Histogram::Null();
00036 static auto* kScanMatcherResidualAngleMetric = metrics::Histogram::Null();
00037 
00038 LocalTrajectoryBuilder2D::LocalTrajectoryBuilder2D(
00039     const proto::LocalTrajectoryBuilderOptions2D& options,
00040     const std::vector<std::string>& expected_range_sensor_ids)
00041     : options_(options),
00042       active_submaps_(options.submaps_options()),
00043       motion_filter_(options_.motion_filter_options()),
00044       real_time_correlative_scan_matcher_(
00045           options_.real_time_correlative_scan_matcher_options()),
00046       ceres_scan_matcher_(options_.ceres_scan_matcher_options()),
00047       range_data_collator_(expected_range_sensor_ids) {}
00048 
00049 LocalTrajectoryBuilder2D::~LocalTrajectoryBuilder2D() {}
00050 
00051 sensor::RangeData
00052 LocalTrajectoryBuilder2D::TransformToGravityAlignedFrameAndFilter(
00053     const transform::Rigid3f& transform_to_gravity_aligned_frame,
00054     const sensor::RangeData& range_data) const {
00055   const sensor::RangeData cropped =
00056       sensor::CropRangeData(sensor::TransformRangeData(
00057                                 range_data, transform_to_gravity_aligned_frame),
00058                             options_.min_z(), options_.max_z());
00059   return sensor::RangeData{
00060       cropped.origin,
00061       sensor::VoxelFilter(options_.voxel_filter_size()).Filter(cropped.returns),
00062       sensor::VoxelFilter(options_.voxel_filter_size()).Filter(cropped.misses)};
00063 }
00064 
00065 std::unique_ptr<transform::Rigid2d> LocalTrajectoryBuilder2D::ScanMatch(
00066     const common::Time time, const transform::Rigid2d& pose_prediction,
00067     const sensor::PointCloud& filtered_gravity_aligned_point_cloud) {
00068   if (active_submaps_.submaps().empty()) {
00069     return absl::make_unique<transform::Rigid2d>(pose_prediction);
00070   }
00071   std::shared_ptr<const Submap2D> matching_submap =
00072       active_submaps_.submaps().front();
00073   // The online correlative scan matcher will refine the initial estimate for
00074   // the Ceres scan matcher.
00075   transform::Rigid2d initial_ceres_pose = pose_prediction;
00076 
00077   if (options_.use_online_correlative_scan_matching()) {
00078     const double score = real_time_correlative_scan_matcher_.Match(
00079         pose_prediction, filtered_gravity_aligned_point_cloud,
00080         *matching_submap->grid(), &initial_ceres_pose);
00081     kRealTimeCorrelativeScanMatcherScoreMetric->Observe(score);
00082   }
00083 
00084   auto pose_observation = absl::make_unique<transform::Rigid2d>();
00085   ceres::Solver::Summary summary;
00086   ceres_scan_matcher_.Match(pose_prediction.translation(), initial_ceres_pose,
00087                             filtered_gravity_aligned_point_cloud,
00088                             *matching_submap->grid(), pose_observation.get(),
00089                             &summary);
00090   if (pose_observation) {
00091     kCeresScanMatcherCostMetric->Observe(summary.final_cost);
00092     const double residual_distance =
00093         (pose_observation->translation() - pose_prediction.translation())
00094             .norm();
00095     kScanMatcherResidualDistanceMetric->Observe(residual_distance);
00096     const double residual_angle =
00097         std::abs(pose_observation->rotation().angle() -
00098                  pose_prediction.rotation().angle());
00099     kScanMatcherResidualAngleMetric->Observe(residual_angle);
00100   }
00101   return pose_observation;
00102 }
00103 
00104 std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
00105 LocalTrajectoryBuilder2D::AddRangeData(
00106     const std::string& sensor_id,
00107     const sensor::TimedPointCloudData& unsynchronized_data) {
00108   auto synchronized_data =
00109       range_data_collator_.AddRangeData(sensor_id, unsynchronized_data);
00110   if (synchronized_data.ranges.empty()) {
00111     LOG(INFO) << "Range data collator filling buffer.";
00112     return nullptr;
00113   }
00114 
00115   const common::Time& time = synchronized_data.time;
00116   // Initialize extrapolator now if we do not ever use an IMU.
00117   if (!options_.use_imu_data()) {
00118     InitializeExtrapolator(time);
00119   }
00120 
00121   if (extrapolator_ == nullptr) {
00122     // Until we've initialized the extrapolator with our first IMU message, we
00123     // cannot compute the orientation of the rangefinder.
00124     LOG(INFO) << "Extrapolator not yet initialized.";
00125     return nullptr;
00126   }
00127 
00128   CHECK(!synchronized_data.ranges.empty());
00129   // TODO(gaschler): Check if this can strictly be 0.
00130   CHECK_LE(synchronized_data.ranges.back().point_time.time, 0.f);
00131   const common::Time time_first_point =
00132       time +
00133       common::FromSeconds(synchronized_data.ranges.front().point_time.time);
00134   if (time_first_point < extrapolator_->GetLastPoseTime()) {
00135     LOG(INFO) << "Extrapolator is still initializing.";
00136     return nullptr;
00137   }
00138 
00139   std::vector<transform::Rigid3f> range_data_poses;
00140   range_data_poses.reserve(synchronized_data.ranges.size());
00141   bool warned = false;
00142   for (const auto& range : synchronized_data.ranges) {
00143     common::Time time_point = time + common::FromSeconds(range.point_time.time);
00144     if (time_point < extrapolator_->GetLastExtrapolatedTime()) {
00145       if (!warned) {
00146         LOG(ERROR)
00147             << "Timestamp of individual range data point jumps backwards from "
00148             << extrapolator_->GetLastExtrapolatedTime() << " to " << time_point;
00149         warned = true;
00150       }
00151       time_point = extrapolator_->GetLastExtrapolatedTime();
00152     }
00153     range_data_poses.push_back(
00154         extrapolator_->ExtrapolatePose(time_point).cast<float>());
00155   }
00156 
00157   if (num_accumulated_ == 0) {
00158     // 'accumulated_range_data_.origin' is uninitialized until the last
00159     // accumulation.
00160     accumulated_range_data_ = sensor::RangeData{{}, {}, {}};
00161   }
00162 
00163   // Drop any returns below the minimum range and convert returns beyond the
00164   // maximum range into misses.
00165   for (size_t i = 0; i < synchronized_data.ranges.size(); ++i) {
00166     const sensor::TimedRangefinderPoint& hit =
00167         synchronized_data.ranges[i].point_time;
00168     const Eigen::Vector3f origin_in_local =
00169         range_data_poses[i] *
00170         synchronized_data.origins.at(synchronized_data.ranges[i].origin_index);
00171     sensor::RangefinderPoint hit_in_local =
00172         range_data_poses[i] * sensor::ToRangefinderPoint(hit);
00173     const Eigen::Vector3f delta = hit_in_local.position - origin_in_local;
00174     const float range = delta.norm();
00175     if (range >= options_.min_range()) {
00176       if (range <= options_.max_range()) {
00177         accumulated_range_data_.returns.push_back(hit_in_local);
00178       } else {
00179         hit_in_local.position =
00180             origin_in_local +
00181             options_.missing_data_ray_length() / range * delta;
00182         accumulated_range_data_.misses.push_back(hit_in_local);
00183       }
00184     }
00185   }
00186   ++num_accumulated_;
00187 
00188   if (num_accumulated_ >= options_.num_accumulated_range_data()) {
00189     const common::Time current_sensor_time = synchronized_data.time;
00190     absl::optional<common::Duration> sensor_duration;
00191     if (last_sensor_time_.has_value()) {
00192       sensor_duration = current_sensor_time - last_sensor_time_.value();
00193     }
00194     last_sensor_time_ = current_sensor_time;
00195     num_accumulated_ = 0;
00196     const transform::Rigid3d gravity_alignment = transform::Rigid3d::Rotation(
00197         extrapolator_->EstimateGravityOrientation(time));
00198     // TODO(gaschler): This assumes that 'range_data_poses.back()' is at time
00199     // 'time'.
00200     accumulated_range_data_.origin = range_data_poses.back().translation();
00201     return AddAccumulatedRangeData(
00202         time,
00203         TransformToGravityAlignedFrameAndFilter(
00204             gravity_alignment.cast<float>() * range_data_poses.back().inverse(),
00205             accumulated_range_data_),
00206         gravity_alignment, sensor_duration);
00207   }
00208   return nullptr;
00209 }
00210 
00211 std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
00212 LocalTrajectoryBuilder2D::AddAccumulatedRangeData(
00213     const common::Time time,
00214     const sensor::RangeData& gravity_aligned_range_data,
00215     const transform::Rigid3d& gravity_alignment,
00216     const absl::optional<common::Duration>& sensor_duration) {
00217   if (gravity_aligned_range_data.returns.empty()) {
00218     LOG(WARNING) << "Dropped empty horizontal range data.";
00219     return nullptr;
00220   }
00221 
00222   // Computes a gravity aligned pose prediction.
00223   const transform::Rigid3d non_gravity_aligned_pose_prediction =
00224       extrapolator_->ExtrapolatePose(time);
00225   const transform::Rigid2d pose_prediction = transform::Project2D(
00226       non_gravity_aligned_pose_prediction * gravity_alignment.inverse());
00227 
00228   const sensor::PointCloud& filtered_gravity_aligned_point_cloud =
00229       sensor::AdaptiveVoxelFilter(options_.adaptive_voxel_filter_options())
00230           .Filter(gravity_aligned_range_data.returns);
00231   if (filtered_gravity_aligned_point_cloud.empty()) {
00232     return nullptr;
00233   }
00234 
00235   // local map frame <- gravity-aligned frame
00236   std::unique_ptr<transform::Rigid2d> pose_estimate_2d =
00237       ScanMatch(time, pose_prediction, filtered_gravity_aligned_point_cloud);
00238   if (pose_estimate_2d == nullptr) {
00239     LOG(WARNING) << "Scan matching failed.";
00240     return nullptr;
00241   }
00242   const transform::Rigid3d pose_estimate =
00243       transform::Embed3D(*pose_estimate_2d) * gravity_alignment;
00244   extrapolator_->AddPose(time, pose_estimate);
00245 
00246   sensor::RangeData range_data_in_local =
00247       TransformRangeData(gravity_aligned_range_data,
00248                          transform::Embed3D(pose_estimate_2d->cast<float>()));
00249   std::unique_ptr<InsertionResult> insertion_result = InsertIntoSubmap(
00250       time, range_data_in_local, filtered_gravity_aligned_point_cloud,
00251       pose_estimate, gravity_alignment.rotation());
00252 
00253   const auto wall_time = std::chrono::steady_clock::now();
00254   if (last_wall_time_.has_value()) {
00255     const auto wall_time_duration = wall_time - last_wall_time_.value();
00256     kLocalSlamLatencyMetric->Set(common::ToSeconds(wall_time_duration));
00257     if (sensor_duration.has_value()) {
00258       kLocalSlamRealTimeRatio->Set(common::ToSeconds(sensor_duration.value()) /
00259                                    common::ToSeconds(wall_time_duration));
00260     }
00261   }
00262   const double thread_cpu_time_seconds = common::GetThreadCpuTimeSeconds();
00263   if (last_thread_cpu_time_seconds_.has_value()) {
00264     const double thread_cpu_duration_seconds =
00265         thread_cpu_time_seconds - last_thread_cpu_time_seconds_.value();
00266     if (sensor_duration.has_value()) {
00267       kLocalSlamCpuRealTimeRatio->Set(
00268           common::ToSeconds(sensor_duration.value()) /
00269           thread_cpu_duration_seconds);
00270     }
00271   }
00272   last_wall_time_ = wall_time;
00273   last_thread_cpu_time_seconds_ = thread_cpu_time_seconds;
00274   return absl::make_unique<MatchingResult>(
00275       MatchingResult{time, pose_estimate, std::move(range_data_in_local),
00276                      std::move(insertion_result)});
00277 }
00278 
00279 std::unique_ptr<LocalTrajectoryBuilder2D::InsertionResult>
00280 LocalTrajectoryBuilder2D::InsertIntoSubmap(
00281     const common::Time time, const sensor::RangeData& range_data_in_local,
00282     const sensor::PointCloud& filtered_gravity_aligned_point_cloud,
00283     const transform::Rigid3d& pose_estimate,
00284     const Eigen::Quaterniond& gravity_alignment) {
00285   if (motion_filter_.IsSimilar(time, pose_estimate)) {
00286     return nullptr;
00287   }
00288   std::vector<std::shared_ptr<const Submap2D>> insertion_submaps =
00289       active_submaps_.InsertRangeData(range_data_in_local);
00290   return absl::make_unique<InsertionResult>(InsertionResult{
00291       std::make_shared<const TrajectoryNode::Data>(TrajectoryNode::Data{
00292           time,
00293           gravity_alignment,
00294           filtered_gravity_aligned_point_cloud,
00295           {},  // 'high_resolution_point_cloud' is only used in 3D.
00296           {},  // 'low_resolution_point_cloud' is only used in 3D.
00297           {},  // 'rotational_scan_matcher_histogram' is only used in 3D.
00298           pose_estimate}),
00299       std::move(insertion_submaps)});
00300 }
00301 
00302 void LocalTrajectoryBuilder2D::AddImuData(const sensor::ImuData& imu_data) {
00303   CHECK(options_.use_imu_data()) << "An unexpected IMU packet was added.";
00304   InitializeExtrapolator(imu_data.time);
00305   extrapolator_->AddImuData(imu_data);
00306 }
00307 
00308 void LocalTrajectoryBuilder2D::AddOdometryData(
00309     const sensor::OdometryData& odometry_data) {
00310   if (extrapolator_ == nullptr) {
00311     // Until we've initialized the extrapolator we cannot add odometry data.
00312     LOG(INFO) << "Extrapolator not yet initialized.";
00313     return;
00314   }
00315   extrapolator_->AddOdometryData(odometry_data);
00316 }
00317 
00318 void LocalTrajectoryBuilder2D::InitializeExtrapolator(const common::Time time) {
00319   if (extrapolator_ != nullptr) {
00320     return;
00321   }
00322   // We derive velocities from poses which are at least 1 ms apart for numerical
00323   // stability. Usually poses known to the extrapolator will be further apart
00324   // in time and thus the last two are used.
00325   constexpr double kExtrapolationEstimationTimeSec = 0.001;
00326   // TODO(gaschler): Consider using InitializeWithImu as 3D does.
00327   extrapolator_ = absl::make_unique<PoseExtrapolator>(
00328       ::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
00329       options_.imu_gravity_time_constant());
00330   extrapolator_->AddPose(time, transform::Rigid3d::Identity());
00331 }
00332 
00333 void LocalTrajectoryBuilder2D::RegisterMetrics(
00334     metrics::FamilyFactory* family_factory) {
00335   auto* latency = family_factory->NewGaugeFamily(
00336       "mapping_2d_local_trajectory_builder_latency",
00337       "Duration from first incoming point cloud in accumulation to local slam "
00338       "result");
00339   kLocalSlamLatencyMetric = latency->Add({});
00340   auto* real_time_ratio = family_factory->NewGaugeFamily(
00341       "mapping_2d_local_trajectory_builder_real_time_ratio",
00342       "sensor duration / wall clock duration.");
00343   kLocalSlamRealTimeRatio = real_time_ratio->Add({});
00344 
00345   auto* cpu_real_time_ratio = family_factory->NewGaugeFamily(
00346       "mapping_2d_local_trajectory_builder_cpu_real_time_ratio",
00347       "sensor duration / cpu duration.");
00348   kLocalSlamCpuRealTimeRatio = cpu_real_time_ratio->Add({});
00349   auto score_boundaries = metrics::Histogram::FixedWidth(0.05, 20);
00350   auto* scores = family_factory->NewHistogramFamily(
00351       "mapping_2d_local_trajectory_builder_scores", "Local scan matcher scores",
00352       score_boundaries);
00353   kRealTimeCorrelativeScanMatcherScoreMetric =
00354       scores->Add({{"scan_matcher", "real_time_correlative"}});
00355   auto cost_boundaries = metrics::Histogram::ScaledPowersOf(2, 0.01, 100);
00356   auto* costs = family_factory->NewHistogramFamily(
00357       "mapping_2d_local_trajectory_builder_costs", "Local scan matcher costs",
00358       cost_boundaries);
00359   kCeresScanMatcherCostMetric = costs->Add({{"scan_matcher", "ceres"}});
00360   auto distance_boundaries = metrics::Histogram::ScaledPowersOf(2, 0.01, 10);
00361   auto* residuals = family_factory->NewHistogramFamily(
00362       "mapping_2d_local_trajectory_builder_residuals",
00363       "Local scan matcher residuals", distance_boundaries);
00364   kScanMatcherResidualDistanceMetric =
00365       residuals->Add({{"component", "distance"}});
00366   kScanMatcherResidualAngleMetric = residuals->Add({{"component", "angle"}});
00367 }
00368 
00369 }  // namespace mapping
00370 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35