#include <pose_graph_data.h>
Public Attributes | |
std::vector < PoseGraphInterface::Constraint > | constraints |
MapById< SubmapId, optimization::SubmapSpec2D > | global_submap_poses_2d |
MapById< SubmapId, optimization::SubmapSpec3D > | global_submap_poses_3d |
std::map< int, PoseGraph::InitialTrajectoryPose > | initial_trajectory_poses |
std::map< std::string, PoseGraphInterface::LandmarkNode > | landmark_nodes |
int | num_trajectory_nodes = 0 |
MapById< SubmapId, InternalSubmapData > | submap_data |
std::map< int, InternalTrajectoryState > | trajectories_state |
TrajectoryConnectivityState | trajectory_connectivity_state |
MapById< NodeId, TrajectoryNode > | trajectory_nodes |
Definition at line 62 of file pose_graph_data.h.
Definition at line 86 of file pose_graph_data.h.
MapById<SubmapId, optimization::SubmapSpec2D> cartographer::mapping::PoseGraphData::global_submap_poses_2d |
Definition at line 68 of file pose_graph_data.h.
MapById<SubmapId, optimization::SubmapSpec3D> cartographer::mapping::PoseGraphData::global_submap_poses_3d |
Definition at line 69 of file pose_graph_data.h.
std::map<int, PoseGraph::InitialTrajectoryPose> cartographer::mapping::PoseGraphData::initial_trajectory_poses |
Definition at line 84 of file pose_graph_data.h.
std::map<std::string , PoseGraphInterface::LandmarkNode> cartographer::mapping::PoseGraphData::landmark_nodes |
Definition at line 76 of file pose_graph_data.h.
Definition at line 80 of file pose_graph_data.h.
Definition at line 65 of file pose_graph_data.h.
Definition at line 81 of file pose_graph_data.h.
Definition at line 79 of file pose_graph_data.h.
Definition at line 72 of file pose_graph_data.h.