Classes | Public Member Functions | Private Member Functions | Private Attributes
cartographer_ros::MapBuilderBridge Class Reference

#include <map_builder_bridge.h>

List of all members.

Classes

struct  LocalTrajectoryData

Public Member Functions

int AddTrajectory (const std::set< ::cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
void FinishTrajectory (int trajectory_id)
visualization_msgs::MarkerArray GetConstraintList ()
visualization_msgs::MarkerArray GetLandmarkPosesList ()
std::unordered_map< int,
LocalTrajectoryData
GetLocalTrajectoryData () LOCKS_EXCLUDED(mutex_)
cartographer_ros_msgs::SubmapList GetSubmapList ()
visualization_msgs::MarkerArray GetTrajectoryNodeList ()
std::map< int,::cartographer::mapping::PoseGraphInterface::TrajectoryState > GetTrajectoryStates ()
void HandleSubmapQuery (cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
void HandleTrajectoryQuery (cartographer_ros_msgs::TrajectoryQuery::Request &request, cartographer_ros_msgs::TrajectoryQuery::Response &response)
void LoadState (const std::string &state_filename, bool load_frozen_state)
 MapBuilderBridge (const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
 MapBuilderBridge (const MapBuilderBridge &)
MapBuilderBridgeoperator= (const MapBuilderBridge &)
void RunFinalOptimization ()
SensorBridgesensor_bridge (int trajectory_id)
bool SerializeState (const std::string &filename, const bool include_unfinished_submaps)

Private Member Functions

std::unordered_map< int,
std::shared_ptr< const
LocalTrajectoryData::LocalSlamData >
> local_slam_data_ 
GUARDED_BY (mutex_)
void OnLocalSlamResult (const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose,::cartographer::sensor::RangeData range_data_in_local) LOCKS_EXCLUDED(mutex_)

Private Attributes

std::unordered_map
< std::string, int > 
landmark_to_index_
std::unique_ptr
< cartographer::mapping::MapBuilderInterface > 
map_builder_
absl::Mutex mutex_
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_
std::unordered_map< int, size_t > trajectory_to_highest_marker_id_

Detailed Description

Definition at line 50 of file map_builder_bridge.h.


Constructor & Destructor Documentation

cartographer_ros::MapBuilderBridge::MapBuilderBridge ( const NodeOptions node_options,
std::unique_ptr< cartographer::mapping::MapBuilderInterface >  map_builder,
tf2_ros::Buffer tf_buffer 
)

Definition at line 100 of file map_builder_bridge.cc.


Member Function Documentation

int cartographer_ros::MapBuilderBridge::AddTrajectory ( const std::set< ::cartographer::mapping::TrajectoryBuilderInterface::SensorId > &  expected_sensor_ids,
const TrajectoryOptions trajectory_options 
)

Definition at line 122 of file map_builder_bridge.cc.

Definition at line 151 of file map_builder_bridge.cc.

visualization_msgs::MarkerArray cartographer_ros::MapBuilderBridge::GetConstraintList ( )

Definition at line 398 of file map_builder_bridge.cc.

visualization_msgs::MarkerArray cartographer_ros::MapBuilderBridge::GetLandmarkPosesList ( )

Definition at line 386 of file map_builder_bridge.cc.

Definition at line 234 of file map_builder_bridge.cc.

cartographer_ros_msgs::SubmapList cartographer_ros::MapBuilderBridge::GetSubmapList ( )

Definition at line 215 of file map_builder_bridge.cc.

visualization_msgs::MarkerArray cartographer_ros::MapBuilderBridge::GetTrajectoryNodeList ( )

Definition at line 286 of file map_builder_bridge.cc.

std::map< int,::cartographer::mapping::PoseGraphInterface::TrajectoryState > cartographer_ros::MapBuilderBridge::GetTrajectoryStates ( )

Definition at line 203 of file map_builder_bridge.cc.

std::unordered_map<int, std::shared_ptr<const LocalTrajectoryData::LocalSlamData> > local_slam_data_ cartographer_ros::MapBuilderBridge::GUARDED_BY ( mutex_  ) [private]
void cartographer_ros::MapBuilderBridge::HandleSubmapQuery ( cartographer_ros_msgs::SubmapQuery::Request &  request,
cartographer_ros_msgs::SubmapQuery::Response &  response 
)

Definition at line 171 of file map_builder_bridge.cc.

void cartographer_ros::MapBuilderBridge::HandleTrajectoryQuery ( cartographer_ros_msgs::TrajectoryQuery::Request &  request,
cartographer_ros_msgs::TrajectoryQuery::Response &  response 
)

Definition at line 262 of file map_builder_bridge.cc.

void cartographer_ros::MapBuilderBridge::LoadState ( const std::string &  state_filename,
bool  load_frozen_state 
)

Definition at line 108 of file map_builder_bridge.cc.

void cartographer_ros::MapBuilderBridge::OnLocalSlamResult ( const int  trajectory_id,
const ::cartographer::common::Time  time,
const ::cartographer::transform::Rigid3d  local_pose,
::cartographer::sensor::RangeData  range_data_in_local 
) [private]

Definition at line 527 of file map_builder_bridge.cc.

MapBuilderBridge& cartographer_ros::MapBuilderBridge::operator= ( const MapBuilderBridge )

Definition at line 160 of file map_builder_bridge.cc.

Definition at line 523 of file map_builder_bridge.cc.

bool cartographer_ros::MapBuilderBridge::SerializeState ( const std::string &  filename,
const bool  include_unfinished_submaps 
)

Definition at line 165 of file map_builder_bridge.cc.


Member Data Documentation

std::unordered_map<std::string , int> cartographer_ros::MapBuilderBridge::landmark_to_index_ [private]

Definition at line 120 of file map_builder_bridge.h.

std::unique_ptr<cartographer::mapping::MapBuilderInterface> cartographer_ros::MapBuilderBridge::map_builder_ [private]

Definition at line 117 of file map_builder_bridge.h.

Definition at line 112 of file map_builder_bridge.h.

Definition at line 113 of file map_builder_bridge.h.

std::unordered_map<int, std::unique_ptr<SensorBridge> > cartographer_ros::MapBuilderBridge::sensor_bridges_ [private]

Definition at line 124 of file map_builder_bridge.h.

Definition at line 118 of file map_builder_bridge.h.

Definition at line 123 of file map_builder_bridge.h.

Definition at line 125 of file map_builder_bridge.h.


The documentation for this class was generated from the following files:


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28