17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H 18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H 23 #include <unordered_map> 27 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" 33 #include "cartographer_ros_msgs/SubmapEntry.h" 34 #include "cartographer_ros_msgs/SubmapList.h" 35 #include "cartographer_ros_msgs/SubmapQuery.h" 36 #include "nav_msgs/OccupancyGrid.h" 37 #include "visualization_msgs/MarkerArray.h" 60 std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
66 void LoadState(
const std::string& state_filename,
bool load_frozen_state);
77 cartographer_ros_msgs::SubmapQuery::Request& request,
78 cartographer_ros_msgs::SubmapQuery::Response& response);
96 TrajectoryBuilderInterface::InsertionResult>
97 insertion_result) EXCLUDES(mutex_);
116 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H
std::unordered_map< int, size_t > trajectory_to_highest_marker_id_
visualization_msgs::MarkerArray GetTrajectoryNodeList()
const NodeOptions node_options_
visualization_msgs::MarkerArray GetConstraintList()
void HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
cartographer::common::Mutex mutex_
std::unordered_map< int, std::shared_ptr< const TrajectoryState::LocalSlamData > > trajectory_state_data_ GUARDED_BY(mutex_)
std::unordered_map< int, TrajectoryState > GetTrajectoryStates() EXCLUDES(mutex_)
void RunFinalOptimization()
std::unordered_map< std::string, int > landmark_to_index_
SensorBridge * sensor_bridge(int trajectory_id)
UniversalTimeScaleClock::time_point Time
tf2_ros::Buffer *const tf_buffer_
visualization_msgs::MarkerArray GetLandmarkPosesList()
void FinishTrajectory(int trajectory_id)
std::set< int > GetFrozenTrajectoryIds()
TrajectoryOptions trajectory_options
cartographer_ros_msgs::SubmapList GetSubmapList()
::cartographer::transform::Rigid3d local_pose
void LoadState(const std::string &state_filename, bool load_frozen_state)
MapBuilderBridge & operator=(const MapBuilderBridge &)=delete
int AddTrajectory(const std::set< ::cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
bool SerializeState(const std::string &filename)
std::shared_ptr< const LocalSlamData > local_slam_data
cartographer::transform::Rigid3d local_to_map
std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder_
std::unique_ptr< cartographer::transform::Rigid3d > published_to_tracking
std::unordered_map< int, TrajectoryOptions > trajectory_options_
void OnLocalSlamResult(const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose, ::cartographer::sensor::RangeData range_data_in_local, const std::unique_ptr< const ::cartographer::mapping::TrajectoryBuilderInterface::InsertionResult > insertion_result) EXCLUDES(mutex_)
::cartographer::common::Time time
MapBuilderBridge(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
::cartographer::sensor::RangeData range_data_in_local
std::unordered_map< int, std::unique_ptr< SensorBridge > > sensor_bridges_