17 #ifndef CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H_ 18 #define CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H_ 21 #include <unordered_map> 22 #include <unordered_set> 25 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" 30 #include "cartographer_ros_msgs/SubmapEntry.h" 31 #include "cartographer_ros_msgs/SubmapList.h" 32 #include "cartographer_ros_msgs/SubmapQuery.h" 33 #include "nav_msgs/OccupancyGrid.h" 34 #include "visualization_msgs/MarkerArray.h" 52 int AddTrajectory(
const std::unordered_set<string>& expected_sensor_ids,
59 cartographer_ros_msgs::SubmapQuery::Request& request,
60 cartographer_ros_msgs::SubmapQuery::Response& response);
81 #endif // CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H_
const NodeOptions node_options_
void WriteAssets(const string &stem)
cartographer::mapping::TrajectoryBuilder::PoseEstimate pose_estimate
SensorBridge * sensor_bridge(int trajectory_id)
tf2_ros::Buffer *const tf_buffer_
void FinishTrajectory(int trajectory_id)
cartographer::mapping::MapBuilder map_builder_
visualization_msgs::MarkerArray GetTrajectoryNodesList()
TrajectoryOptions trajectory_options
cartographer_ros_msgs::SubmapList GetSubmapList()
void SerializeState(const string &stem)
MapBuilderBridge & operator=(const MapBuilderBridge &)=delete
MapBuilderBridge(const NodeOptions &node_options, tf2_ros::Buffer *tf_buffer)
cartographer::transform::Rigid3d local_to_map
std::unique_ptr< cartographer::transform::Rigid3d > published_to_tracking
bool HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
std::unordered_map< int, TrajectoryOptions > trajectory_options_
std::unordered_map< int, TrajectoryState > GetTrajectoryStates()
int AddTrajectory(const std::unordered_set< string > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
std::unique_ptr< nav_msgs::OccupancyGrid > BuildOccupancyGrid()
std::unordered_map< int, std::unique_ptr< SensorBridge > > sensor_bridges_