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" 41 const mapping::proto::LocalTrajectoryBuilderOptions3D& options,
42 const std::vector<std::string>& expected_range_sensor_ids)
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(), {}, {}},
65 constexpr
double kExtrapolationEstimationTimeSec = 0.001;
68 options_.imu_gravity_time_constant(), imu_data);
71 std::unique_ptr<LocalTrajectoryBuilder3D::MatchingResult>
73 const std::string& sensor_id,
75 auto synchronized_data =
77 if (synchronized_data.ranges.empty()) {
78 LOG(INFO) <<
"Range data collator filling buffer.";
86 LOG(INFO) <<
"IMU not yet initialized.";
90 CHECK(!synchronized_data.ranges.empty());
91 CHECK_LE(synchronized_data.ranges.back().point_time[3], 0.f);
95 if (time_first_point < extrapolator_->GetLastPoseTime()) {
96 LOG(INFO) <<
"Extrapolator is still initializing.";
104 std::vector<sensor::TimedPointCloudOriginData::RangeMeasurement> hits =
106 .Filter(synchronized_data.ranges);
108 std::vector<transform::Rigid3f> hits_poses;
109 hits_poses.reserve(hits.size());
111 for (
const auto& hit : hits) {
113 if (time_point < extrapolator_->GetLastExtrapolatedTime()) {
116 <<
"Timestamp of individual range data point jumps backwards from " 117 <<
extrapolator_->GetLastExtrapolatedTime() <<
" to " << time_point;
122 hits_poses.push_back(
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()) {
146 origin_in_local +
options_.max_range() / range * delta);
169 std::unique_ptr<LocalTrajectoryBuilder3D::MatchingResult>
173 if (filtered_range_data_in_tracking.
returns.empty()) {
174 LOG(WARNING) <<
"Dropped empty range data.";
181 std::shared_ptr<const mapping::Submap3D> matching_submap =
184 matching_submap->local_pose().
inverse() * pose_prediction;
186 options_.high_resolution_adaptive_voxel_filter_options());
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.";
193 if (
options_.use_online_correlative_scan_matching()) {
197 initial_pose, high_resolution_point_cloud_in_tracking,
198 matching_submap->high_resolution_hybrid_grid(), &initial_ceres_pose);
203 ceres::Solver::Summary summary;
206 options_.low_resolution_adaptive_voxel_filter_options());
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.";
215 (matching_submap->local_pose().inverse() * pose_prediction).translation(),
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);
223 double residual_distance = (pose_observation_in_submap.
translation() -
227 double residual_angle = pose_observation_in_submap.
rotation().angularDistance(
231 matching_submap->local_pose() * pose_observation_in_submap;
233 const Eigen::Quaterniond gravity_alignment =
237 filtered_range_data_in_tracking, pose_estimate.
cast<
float>());
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);
244 std::chrono::duration_cast<std::chrono::seconds>(duration).
count());
246 time, pose_estimate, std::move(filtered_range_data_in_local),
247 std::move(insertion_result)});
254 LOG(INFO) <<
"Extrapolator not yet initialized.";
260 std::unique_ptr<LocalTrajectoryBuilder3D::InsertionResult>
268 const Eigen::Quaterniond& gravity_alignment) {
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);
281 const Eigen::VectorXf rotational_scan_matcher_histogram =
284 filtered_range_data_in_tracking.
returns,
286 options_.rotational_histogram_size());
287 return common::make_unique<InsertionResult>(
293 high_resolution_point_cloud_in_tracking,
294 low_resolution_point_cloud_in_tracking,
295 rotational_scan_matcher_histogram,
297 std::move(insertion_submaps)});
303 "mapping_internal_3d_local_trajectory_builder_latency",
304 "Duration from first incoming point cloud in accumulation to local slam " 309 "mapping_internal_3d_local_trajectory_builder_scores",
310 "Local scan matcher scores", score_boundaries);
312 scores->Add({{
"scan_matcher",
"real_time_correlative"}});
315 "mapping_internal_3d_local_trajectory_builder_costs",
316 "Local scan matcher costs", cost_boundaries);
320 "mapping_internal_3d_local_trajectory_builder_residuals",
321 "Local scan matcher residuals", distance_boundaries);
323 residuals->Add({{
"component",
"distance"}});
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
PointCloud Filter(const PointCloud &point_cloud) const
void AddOdometryData(const sensor::OdometryData &odometry_data)
RangeDataCollator range_data_collator_
static auto * kLocalSlamLatencyMetric
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)
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
void AddImuData(const sensor::ImuData &imu_data)
static auto * kScanMatcherResidualAngleMetric
static auto * kCeresScanMatcherCostMetric
std::unique_ptr< ActiveSubmaps2D > active_submaps_
mapping::MotionFilter motion_filter_
static Histogram * Null()
UniversalTimeScaleClock::time_point Time
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
~LocalTrajectoryBuilder3D()
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)
Duration FromSeconds(const double seconds)
proto::ProbabilityGridRangeDataInserterOptions2D options_
sensor::RangeData accumulated_range_data_
static BucketBoundaries FixedWidth(double width, int num_finite_buckets)
std::vector< std::shared_ptr< Submap3D > > submaps() const
static auto * kScanMatcherResidualDistanceMetric
std::vector< Eigen::Vector3f > PointCloud
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)
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)
std::unique_ptr< mapping::PoseExtrapolator > extrapolator_
mapping::ActiveSubmaps3D active_submaps_