#include <local_trajectory_builder_3d.h>
Classes | |
struct | InsertionResult |
struct | MatchingResult |
Public Member Functions | |
void | AddImuData (const sensor::ImuData &imu_data) |
void | AddOdometryData (const sensor::OdometryData &odometry_data) |
std::unique_ptr< MatchingResult > | AddRangeData (const std::string &sensor_id, const sensor::TimedPointCloudData &range_data) |
LocalTrajectoryBuilder3D (const mapping::proto::LocalTrajectoryBuilderOptions3D &options, const std::vector< std::string > &expected_range_sensor_ids) | |
LocalTrajectoryBuilder3D (const LocalTrajectoryBuilder3D &) | |
LocalTrajectoryBuilder3D & | operator= (const LocalTrajectoryBuilder3D &) |
~LocalTrajectoryBuilder3D () | |
Static Public Member Functions | |
static void | RegisterMetrics (metrics::FamilyFactory *family_factory) |
Private Member Functions | |
std::unique_ptr< MatchingResult > | AddAccumulatedRangeData (common::Time time, const sensor::RangeData &filtered_range_data_in_tracking, const absl::optional< common::Duration > &sensor_duration) |
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 < transform::Rigid3d > | ScanMatch (const transform::Rigid3d &pose_prediction, const sensor::PointCloud &low_resolution_point_cloud_in_tracking, const sensor::PointCloud &high_resolution_point_cloud_in_tracking) |
Private Attributes | |
sensor::RangeData | accumulated_range_data_ |
mapping::ActiveSubmaps3D | active_submaps_ |
std::unique_ptr < scan_matching::CeresScanMatcher3D > | ceres_scan_matcher_ |
std::unique_ptr < mapping::PoseExtrapolator > | extrapolator_ |
absl::optional< common::Time > | last_sensor_time_ |
absl::optional< double > | last_thread_cpu_time_seconds_ |
absl::optional < std::chrono::steady_clock::time_point > | last_wall_time_ |
mapping::MotionFilter | motion_filter_ |
int | num_accumulated_ = 0 |
const mapping::proto::LocalTrajectoryBuilderOptions3D | options_ |
RangeDataCollator | range_data_collator_ |
std::unique_ptr < scan_matching::RealTimeCorrelativeScanMatcher3D > | real_time_correlative_scan_matcher_ |
Definition at line 43 of file local_trajectory_builder_3d.h.
cartographer::mapping::LocalTrajectoryBuilder3D::LocalTrajectoryBuilder3D | ( | const mapping::proto::LocalTrajectoryBuilderOptions3D & | options, |
const std::vector< std::string > & | expected_range_sensor_ids | ||
) | [explicit] |
Definition at line 47 of file local_trajectory_builder_3d.cc.
Definition at line 61 of file local_trajectory_builder_3d.cc.
cartographer::mapping::LocalTrajectoryBuilder3D::LocalTrajectoryBuilder3D | ( | const LocalTrajectoryBuilder3D & | ) |
std::unique_ptr< LocalTrajectoryBuilder3D::MatchingResult > cartographer::mapping::LocalTrajectoryBuilder3D::AddAccumulatedRangeData | ( | common::Time | time, |
const sensor::RangeData & | filtered_range_data_in_tracking, | ||
const absl::optional< common::Duration > & | sensor_duration | ||
) | [private] |
Definition at line 237 of file local_trajectory_builder_3d.cc.
void cartographer::mapping::LocalTrajectoryBuilder3D::AddImuData | ( | const sensor::ImuData & | imu_data | ) |
Definition at line 106 of file local_trajectory_builder_3d.cc.
void cartographer::mapping::LocalTrajectoryBuilder3D::AddOdometryData | ( | const sensor::OdometryData & | odometry_data | ) |
Definition at line 333 of file local_trajectory_builder_3d.cc.
std::unique_ptr< LocalTrajectoryBuilder3D::MatchingResult > cartographer::mapping::LocalTrajectoryBuilder3D::AddRangeData | ( | const std::string & | sensor_id, |
const sensor::TimedPointCloudData & | range_data | ||
) |
Definition at line 121 of file local_trajectory_builder_3d.cc.
std::unique_ptr< LocalTrajectoryBuilder3D::InsertionResult > cartographer::mapping::LocalTrajectoryBuilder3D::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 | ||
) | [private] |
Definition at line 344 of file local_trajectory_builder_3d.cc.
LocalTrajectoryBuilder3D& cartographer::mapping::LocalTrajectoryBuilder3D::operator= | ( | const LocalTrajectoryBuilder3D & | ) |
void cartographer::mapping::LocalTrajectoryBuilder3D::RegisterMetrics | ( | metrics::FamilyFactory * | family_factory | ) | [static] |
Definition at line 381 of file local_trajectory_builder_3d.cc.
std::unique_ptr< transform::Rigid3d > cartographer::mapping::LocalTrajectoryBuilder3D::ScanMatch | ( | const transform::Rigid3d & | pose_prediction, |
const sensor::PointCloud & | low_resolution_point_cloud_in_tracking, | ||
const sensor::PointCloud & | high_resolution_point_cloud_in_tracking | ||
) | [private] |
Definition at line 63 of file local_trajectory_builder_3d.cc.
sensor::RangeData cartographer::mapping::LocalTrajectoryBuilder3D::accumulated_range_data_ [private] |
Definition at line 109 of file local_trajectory_builder_3d.h.
Definition at line 99 of file local_trajectory_builder_3d.h.
std::unique_ptr<scan_matching::CeresScanMatcher3D> cartographer::mapping::LocalTrajectoryBuilder3D::ceres_scan_matcher_ [private] |
Definition at line 104 of file local_trajectory_builder_3d.h.
std::unique_ptr<mapping::PoseExtrapolator> cartographer::mapping::LocalTrajectoryBuilder3D::extrapolator_ [private] |
Definition at line 106 of file local_trajectory_builder_3d.h.
absl::optional<common::Time> cartographer::mapping::LocalTrajectoryBuilder3D::last_sensor_time_ [private] |
Definition at line 116 of file local_trajectory_builder_3d.h.
absl::optional<double> cartographer::mapping::LocalTrajectoryBuilder3D::last_thread_cpu_time_seconds_ [private] |
Definition at line 112 of file local_trajectory_builder_3d.h.
absl::optional<std::chrono::steady_clock::time_point> cartographer::mapping::LocalTrajectoryBuilder3D::last_wall_time_ [private] |
Definition at line 110 of file local_trajectory_builder_3d.h.
Definition at line 101 of file local_trajectory_builder_3d.h.
int cartographer::mapping::LocalTrajectoryBuilder3D::num_accumulated_ = 0 [private] |
Definition at line 108 of file local_trajectory_builder_3d.h.
const mapping::proto::LocalTrajectoryBuilderOptions3D cartographer::mapping::LocalTrajectoryBuilder3D::options_ [private] |
Definition at line 98 of file local_trajectory_builder_3d.h.
Definition at line 114 of file local_trajectory_builder_3d.h.
std::unique_ptr<scan_matching::RealTimeCorrelativeScanMatcher3D> cartographer::mapping::LocalTrajectoryBuilder3D::real_time_correlative_scan_matcher_ [private] |
Definition at line 103 of file local_trajectory_builder_3d.h.