17 #ifndef CARTOGRAPHER_MAPPING_GLOBAL_TRAJECTORY_BUILDER_INTERFACE_H_ 18 #define CARTOGRAPHER_MAPPING_GLOBAL_TRAJECTORY_BUILDER_INTERFACE_H_ 57 const Eigen::Vector3f& origin,
60 const Eigen::Vector3d& linear_acceleration,
61 const Eigen::Vector3d& angular_velocity) = 0;
69 #endif // CARTOGRAPHER_MAPPING_GLOBAL_TRAJECTORY_BUILDER_INTERFACE_H_
virtual int num_submaps()=0
virtual SubmapData GetSubmapData(int submap_index)=0
UniversalTimeScaleClock::time_point Time
virtual const PoseEstimate & pose_estimate() const =0
virtual void AddOdometerData(common::Time time, const transform::Rigid3d &pose)=0
std::vector< Eigen::Vector3f > PointCloud
GlobalTrajectoryBuilderInterface & operator=(const GlobalTrajectoryBuilderInterface &)=delete
virtual void AddRangefinderData(common::Time time, const Eigen::Vector3f &origin, const sensor::PointCloud &ranges)=0
GlobalTrajectoryBuilderInterface()
virtual ~GlobalTrajectoryBuilderInterface()
virtual void AddImuData(common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)=0