17 #ifndef CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_ 18 #define CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_ 28 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" 40 common::LuaParameterDictionary*
const parameter_dictionary);
42 class LocalSlamResultData;
63 std::unique_ptr<const InsertionResult>)>;
79 return std::forward_as_tuple(type,
id) ==
80 std::forward_as_tuple(other.
type, other.
id);
84 return std::forward_as_tuple(type,
id) <
85 std::forward_as_tuple(other.
type, other.
id);
97 const std::string& sensor_id,
104 const std::string& sensor_id,
112 std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) = 0;
122 #endif // CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_ PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
std::vector< std::shared_ptr< const Submap > > insertion_submaps
TrajectoryBuilderInterface()
bool operator<(const SensorId &other) const
virtual ~TrajectoryBuilderInterface()
UniversalTimeScaleClock::time_point Time
TrajectoryBuilderInterface & operator=(const TrajectoryBuilderInterface &)=delete
proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
virtual void AddLocalSlamResultData(std::unique_ptr< mapping::LocalSlamResultData > local_slam_result_data)=0
bool operator==(const SensorId &other) const
proto::MapLimits ToProto(const MapLimits &map_limits)
virtual void AddSensorData(const std::string &sensor_id, const sensor::TimedPointCloudData &timed_point_cloud_data)=0
std::shared_ptr< const TrajectoryNode::Data > constant_data
::cartographer::mapping::TrajectoryBuilderInterface::SensorId SensorId
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback