17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_ 30 #include "cartographer/mapping/proto/3d/local_trajectory_builder_options_3d.pb.h" 58 const mapping::proto::LocalTrajectoryBuilderOptions3D& options,
59 const std::vector<std::string>& expected_range_sensor_ids);
71 const std::string& sensor_id,
88 const Eigen::Quaterniond& gravity_alignment);
90 const mapping::proto::LocalTrajectoryBuilderOptions3D
options_;
94 std::unique_ptr<scan_matching::RealTimeCorrelativeScanMatcher3D>
110 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_ transform::Rigid3d local_pose
void AddOdometryData(const sensor::OdometryData &odometry_data)
RangeDataCollator range_data_collator_
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
void AddImuData(const sensor::ImuData &imu_data)
mapping::MotionFilter motion_filter_
sensor::RangeData range_data_in_local
UniversalTimeScaleClock::time_point Time
std::unique_ptr< MatchingResult > AddRangeData(const std::string &sensor_id, const sensor::TimedPointCloudData &range_data)
~LocalTrajectoryBuilder3D()
std::unique_ptr< const InsertionResult > insertion_result
sensor::RangeData accumulated_range_data_
std::vector< Eigen::Vector3f > PointCloud
LocalTrajectoryBuilder3D & operator=(const LocalTrajectoryBuilder3D &)=delete
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_
std::chrono::steady_clock::time_point accumulation_started_
const mapping::proto::LocalTrajectoryBuilderOptions3D options_
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_
std::unique_ptr< mapping::PoseExtrapolator > extrapolator_
mapping::ActiveSubmaps3D active_submaps_
std::shared_ptr< const mapping::TrajectoryNode::Data > constant_data
std::vector< std::shared_ptr< const mapping::Submap3D > > insertion_submaps