Class MapBuilderBridge
Defined in File map_builder_bridge.h
Nested Relationships
Nested Types
Class Documentation
-
class MapBuilderBridge
Public Functions
-
MapBuilderBridge(const NodeOptions &node_options, std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder, tf2_ros::Buffer *tf_buffer)
-
MapBuilderBridge(const MapBuilderBridge&) = delete
-
MapBuilderBridge &operator=(const MapBuilderBridge&) = delete
-
void LoadState(const std::string &state_filename, bool load_frozen_state)
-
int AddTrajectory(const std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId> &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
-
void FinishTrajectory(int trajectory_id)
-
void RunFinalOptimization()
-
bool SerializeState(const std::string &filename, const bool include_unfinished_submaps)
-
std::map<int, ::cartographer::mapping::PoseGraphInterface::TrajectoryState> GetTrajectoryStates()
- std::unordered_map< int, LocalTrajectoryData > GetLocalTrajectoryData () LOCKS_EXCLUDED(mutex_)
-
SensorBridge *sensor_bridge(int trajectory_id)
-
struct LocalTrajectoryData
Public Members
-
std::shared_ptr<const LocalSlamData> local_slam_data
-
TrajectoryOptions trajectory_options
-
struct LocalSlamData
-
std::shared_ptr<const LocalSlamData> local_slam_data
-
MapBuilderBridge(const NodeOptions &node_options, std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder, tf2_ros::Buffer *tf_buffer)