37 const proto::LocalTrajectoryBuilderOptions2D& options,
38 const std::vector<std::string>& expected_range_sensor_ids)
41 motion_filter_(
options_.motion_filter_options()),
43 options_.real_time_correlative_scan_matcher_options()),
45 range_data_collator_(expected_range_sensor_ids) {}
55 range_data, transform_to_gravity_aligned_frame),
66 std::shared_ptr<const Submap2D> matching_submap =
72 options_.adaptive_voxel_filter_options());
74 adaptive_voxel_filter.
Filter(gravity_aligned_range_data.
returns);
75 if (filtered_gravity_aligned_point_cloud.empty()) {
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()),
88 auto pose_observation = common::make_unique<transform::Rigid2d>();
89 ceres::Solver::Summary summary;
91 filtered_gravity_aligned_point_cloud,
92 *matching_submap->grid(), pose_observation.get(),
94 if (pose_observation) {
96 double residual_distance =
97 (pose_observation->translation() - pose_prediction.
translation())
100 double residual_angle = std::abs(pose_observation->rotation().angle() -
101 pose_prediction.
rotation().angle());
104 return pose_observation;
107 std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
109 const std::string& sensor_id,
111 auto synchronized_data =
113 if (synchronized_data.ranges.empty()) {
114 LOG(INFO) <<
"Range data collator filling buffer.";
127 LOG(INFO) <<
"Extrapolator not yet initialized.";
131 CHECK(!synchronized_data.ranges.empty());
133 CHECK_LE(synchronized_data.ranges.back().point_time[3], 0.f);
137 if (time_first_point < extrapolator_->GetLastPoseTime()) {
138 LOG(INFO) <<
"Extrapolator is still initializing.";
146 std::vector<transform::Rigid3f> range_data_poses;
147 range_data_poses.reserve(synchronized_data.ranges.size());
149 for (
const auto& range : synchronized_data.ranges) {
151 if (time_point < extrapolator_->GetLastExtrapolatedTime()) {
154 <<
"Timestamp of individual range data point jumps backwards from " 155 <<
extrapolator_->GetLastExtrapolatedTime() <<
" to " << time_point;
160 range_data_poses.push_back(
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()) {
186 options_.missing_data_ray_length() / range * delta);
202 gravity_alignment.
cast<
float>() * range_data_poses.back().inverse(),
209 std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
214 if (gravity_aligned_range_data.
returns.empty()) {
215 LOG(WARNING) <<
"Dropped empty horizontal range data.";
223 non_gravity_aligned_pose_prediction * gravity_alignment.
inverse());
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.";
239 std::unique_ptr<InsertionResult> insertion_result =
241 pose_estimate, gravity_alignment.
rotation());
244 std::chrono::duration_cast<std::chrono::seconds>(duration).
count());
245 return common::make_unique<MatchingResult>(
247 std::move(insertion_result)});
250 std::unique_ptr<LocalTrajectoryBuilder2D::InsertionResult>
255 const Eigen::Quaterniond& gravity_alignment) {
262 std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;
264 insertion_submaps.push_back(submap);
269 options_.loop_closure_adaptive_voxel_filter_options());
271 adaptive_voxel_filter.
Filter(gravity_aligned_range_data.
returns);
277 filtered_gravity_aligned_point_cloud,
282 std::move(insertion_submaps)});
286 CHECK(
options_.use_imu_data()) <<
"An unexpected IMU packet was added.";
295 LOG(INFO) <<
"Extrapolator not yet initialized.";
308 constexpr
double kExtrapolationEstimationTimeSec = 0.001;
312 options_.imu_gravity_time_constant());
319 "mapping_internal_2d_local_trajectory_builder_latency",
320 "Duration from first incoming point cloud in accumulation to local slam " 325 "mapping_internal_2d_local_trajectory_builder_scores",
326 "Local scan matcher scores", score_boundaries);
328 scores->Add({{
"scan_matcher",
"fast_correlative"}});
331 "mapping_internal_2d_local_trajectory_builder_costs",
332 "Local scan matcher costs", cost_boundaries);
336 "mapping_internal_2d_local_trajectory_builder_residuals",
337 "Local scan matcher residuals", distance_boundaries);
339 residuals->Add({{
"component",
"distance"}});
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 auto * kLocalSlamLatencyMetric
~LocalTrajectoryBuilder2D()
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_
static auto * kScanMatcherResidualAngleMetric
static auto * kCeresScanMatcherCostMetric
ActiveSubmaps2D active_submaps_
std::vector< std::shared_ptr< Submap2D > > submaps() const
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
std::unique_ptr< ActiveSubmaps2D > active_submaps_
scan_matching::RealTimeCorrelativeScanMatcher2D real_time_correlative_scan_matcher_
void InitializeExtrapolator(common::Time time)
static Histogram * Null()
void InsertRangeData(const sensor::RangeData &range_data)
UniversalTimeScaleClock::time_point Time
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)
LocalTrajectoryBuilder2D(const proto::LocalTrajectoryBuilderOptions2D &options, const std::vector< std::string > &expected_range_sensor_ids)
std::chrono::steady_clock::time_point accumulation_started_
Duration FromSeconds(const double seconds)
std::unique_ptr< PoseExtrapolator > extrapolator_
proto::ProbabilityGridRangeDataInserterOptions2D options_
static BucketBoundaries FixedWidth(double width, int num_finite_buckets)
MotionFilter motion_filter_
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
void AddImuData(const sensor::ImuData &imu_data)
std::vector< Eigen::Vector3f > PointCloud
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
bool IsSimilar(common::Time time, const transform::Rigid3d &pose)
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)
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
sensor::RangeData accumulated_range_data_
scan_matching::CeresScanMatcher2D ceres_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)
std::unique_ptr< transform::Rigid2d > ScanMatch(common::Time time, const transform::Rigid2d &pose_prediction, const sensor::RangeData &gravity_aligned_range_data)
RangeDataCollator range_data_collator_