#include <map_builder_bridge.h>
Classes | |
| struct | TrajectoryState |
Public Member Functions | |
| int | AddTrajectory (const std::unordered_set< string > &expected_sensor_ids, const TrajectoryOptions &trajectory_options) |
| std::unique_ptr< nav_msgs::OccupancyGrid > | BuildOccupancyGrid () |
| void | FinishTrajectory (int trajectory_id) |
| cartographer_ros_msgs::SubmapList | GetSubmapList () |
| visualization_msgs::MarkerArray | GetTrajectoryNodesList () |
| std::unordered_map< int, TrajectoryState > | GetTrajectoryStates () |
| bool | HandleSubmapQuery (cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response) |
| MapBuilderBridge (const NodeOptions &node_options, tf2_ros::Buffer *tf_buffer) | |
| MapBuilderBridge (const MapBuilderBridge &)=delete | |
| MapBuilderBridge & | operator= (const MapBuilderBridge &)=delete |
| SensorBridge * | sensor_bridge (int trajectory_id) |
| void | SerializeState (const string &stem) |
| void | WriteAssets (const string &stem) |
Private Attributes | |
| cartographer::mapping::MapBuilder | map_builder_ |
| const NodeOptions | node_options_ |
| std::unordered_map< int, std::unique_ptr< SensorBridge > > | sensor_bridges_ |
| tf2_ros::Buffer *const | tf_buffer_ |
| std::unordered_map< int, TrajectoryOptions > | trajectory_options_ |
Definition at line 38 of file map_builder_bridge.h.
| cartographer_ros::MapBuilderBridge::MapBuilderBridge | ( | const NodeOptions & | node_options, |
| tf2_ros::Buffer * | tf_buffer | ||
| ) |
Definition at line 29 of file map_builder_bridge.cc.
|
delete |
| int cartographer_ros::MapBuilderBridge::AddTrajectory | ( | const std::unordered_set< string > & | expected_sensor_ids, |
| const TrajectoryOptions & | trajectory_options | ||
| ) |
Definition at line 35 of file map_builder_bridge.cc.
| std::unique_ptr< nav_msgs::OccupancyGrid > cartographer_ros::MapBuilderBridge::BuildOccupancyGrid | ( | ) |
Definition at line 150 of file map_builder_bridge.cc.
| void cartographer_ros::MapBuilderBridge::FinishTrajectory | ( | int | trajectory_id | ) |
Definition at line 54 of file map_builder_bridge.cc.
| cartographer_ros_msgs::SubmapList cartographer_ros::MapBuilderBridge::GetSubmapList | ( | ) |
Definition at line 126 of file map_builder_bridge.cc.
| visualization_msgs::MarkerArray cartographer_ros::MapBuilderBridge::GetTrajectoryNodesList | ( | ) |
Definition at line 203 of file map_builder_bridge.cc.
| std::unordered_map< int, MapBuilderBridge::TrajectoryState > cartographer_ros::MapBuilderBridge::GetTrajectoryStates | ( | ) |
Definition at line 176 of file map_builder_bridge.cc.
| bool cartographer_ros::MapBuilderBridge::HandleSubmapQuery | ( | cartographer_ros_msgs::SubmapQuery::Request & | request, |
| cartographer_ros_msgs::SubmapQuery::Response & | response | ||
| ) |
Definition at line 104 of file map_builder_bridge.cc.
|
delete |
| SensorBridge * cartographer_ros::MapBuilderBridge::sensor_bridge | ( | int | trajectory_id | ) |
Definition at line 242 of file map_builder_bridge.cc.
| void cartographer_ros::MapBuilderBridge::SerializeState | ( | const string & | stem | ) |
Definition at line 63 of file map_builder_bridge.cc.
| void cartographer_ros::MapBuilderBridge::WriteAssets | ( | const string & | stem | ) |
Definition at line 73 of file map_builder_bridge.cc.
|
private |
Definition at line 71 of file map_builder_bridge.h.
|
private |
Definition at line 70 of file map_builder_bridge.h.
|
private |
Definition at line 76 of file map_builder_bridge.h.
|
private |
Definition at line 72 of file map_builder_bridge.h.
|
private |
Definition at line 75 of file map_builder_bridge.h.