Public Member Functions | Private Member Functions | Private Attributes | List of all members
cartographer_ros::Node Class Reference

#include <node.h>

Public Member Functions

void FinishAllTrajectories ()
 
MapBuilderBridgemap_builder_bridge ()
 
 Node (const NodeOptions &node_options, tf2_ros::Buffer *tf_buffer)
 
 Node (const Node &)=delete
 
::ros::NodeHandlenode_handle ()
 
Nodeoperator= (const Node &)=delete
 
void StartTrajectoryWithDefaultTopics (const TrajectoryOptions &options)
 
 ~Node ()
 

Private Member Functions

int AddTrajectory (const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics)
 
MapBuilderBridge map_builder_bridge_ GUARDED_BY (mutex_)
 
std::unordered_map< int, bool > is_active_trajectory_ GUARDED_BY (mutex_)
 
bool HandleFinishTrajectory (cartographer_ros_msgs::FinishTrajectory::Request &request, cartographer_ros_msgs::FinishTrajectory::Response &response)
 
bool HandleStartTrajectory (cartographer_ros_msgs::StartTrajectory::Request &request, cartographer_ros_msgs::StartTrajectory::Response &response)
 
bool HandleSubmapQuery (cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
 
bool HandleWriteAssets (cartographer_ros_msgs::WriteAssets::Request &request, cartographer_ros_msgs::WriteAssets::Response &response)
 
void LaunchSubscribers (const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics, int trajectory_id)
 
void PublishSubmapList (const ::ros::WallTimerEvent &timer_event)
 
void PublishTrajectoryNodesList (const ::ros::WallTimerEvent &timer_event)
 
void PublishTrajectoryStates (const ::ros::WallTimerEvent &timer_event)
 
void SpinOccupancyGridThreadForever ()
 
bool ValidateTopicName (const ::cartographer_ros_msgs::SensorTopics &topics, const TrajectoryOptions &options)
 
bool ValidateTrajectoryOptions (const TrajectoryOptions &options)
 

Private Attributes

std::unordered_map< int,::ros::Subscriberimu_subscribers_
 
std::unordered_map< int,::ros::Subscriberlaser_scan_subscribers_
 
cartographer::common::Time last_scan_matched_point_cloud_time_
 
std::unordered_map< int,::ros::Subscribermulti_echo_laser_scan_subscribers_
 
cartographer::common::Mutex mutex_
 
::ros::NodeHandle node_handle_
 
const NodeOptions node_options_
 
::ros::Publisher occupancy_grid_publisher_
 
std::thread occupancy_grid_thread_
 
std::unordered_map< int,::ros::Subscriberodom_subscribers_
 
std::unordered_map< int, std::vector<::ros::Subscriber > > point_cloud_subscribers_
 
::ros::Publisher scan_matched_point_cloud_publisher_
 
std::vector<::ros::ServiceServerservice_servers_
 
::ros::Publisher submap_list_publisher_
 
bool terminating_ = false GUARDED_BY(mutex_)
 
tf2_ros::TransformBroadcaster tf_broadcaster_
 
::ros::Publisher trajectory_nodes_list_publisher_
 
std::vector<::ros::WallTimerwall_timers_
 

Detailed Description

Definition at line 57 of file node.h.

Constructor & Destructor Documentation

cartographer_ros::Node::Node ( const NodeOptions node_options,
tf2_ros::Buffer tf_buffer 
)

Definition at line 100 of file node.cc.

cartographer_ros::Node::~Node ( )

Definition at line 143 of file node.cc.

cartographer_ros::Node::Node ( const Node )
delete

Member Function Documentation

int cartographer_ros::Node::AddTrajectory ( const TrajectoryOptions options,
const cartographer_ros_msgs::SensorTopics &  topics 
)
private

Definition at line 258 of file node.cc.

void cartographer_ros::Node::FinishAllTrajectories ( )

Definition at line 493 of file node.cc.

MapBuilderBridge map_builder_bridge_ cartographer_ros::Node::GUARDED_BY ( mutex_  )
private
std::unordered_map<int, bool> is_active_trajectory_ cartographer_ros::Node::GUARDED_BY ( mutex_  )
private
bool cartographer_ros::Node::HandleFinishTrajectory ( cartographer_ros_msgs::FinishTrajectory::Request &  request,
cartographer_ros_msgs::FinishTrajectory::Response &  response 
)
private

Definition at line 452 of file node.cc.

bool cartographer_ros::Node::HandleStartTrajectory ( cartographer_ros_msgs::StartTrajectory::Request &  request,
cartographer_ros_msgs::StartTrajectory::Response &  response 
)
private

Definition at line 415 of file node.cc.

bool cartographer_ros::Node::HandleSubmapQuery ( cartographer_ros_msgs::SubmapQuery::Request &  request,
cartographer_ros_msgs::SubmapQuery::Response &  response 
)
private

Definition at line 157 of file node.cc.

bool cartographer_ros::Node::HandleWriteAssets ( cartographer_ros_msgs::WriteAssets::Request &  request,
cartographer_ros_msgs::WriteAssets::Response &  response 
)
private

Definition at line 484 of file node.cc.

void cartographer_ros::Node::LaunchSubscribers ( const TrajectoryOptions options,
const cartographer_ros_msgs::SensorTopics &  topics,
int  trajectory_id 
)
private

Definition at line 287 of file node.cc.

MapBuilderBridge * cartographer_ros::Node::map_builder_bridge ( )

Definition at line 155 of file node.cc.

ros::NodeHandle * cartographer_ros::Node::node_handle ( )

Definition at line 153 of file node.cc.

Node& cartographer_ros::Node::operator= ( const Node )
delete
void cartographer_ros::Node::PublishSubmapList ( const ::ros::WallTimerEvent timer_event)
private

Definition at line 164 of file node.cc.

void cartographer_ros::Node::PublishTrajectoryNodesList ( const ::ros::WallTimerEvent timer_event)
private

Definition at line 230 of file node.cc.

void cartographer_ros::Node::PublishTrajectoryStates ( const ::ros::WallTimerEvent timer_event)
private

Definition at line 169 of file node.cc.

void cartographer_ros::Node::SpinOccupancyGridThreadForever ( )
private

Definition at line 239 of file node.cc.

void cartographer_ros::Node::StartTrajectoryWithDefaultTopics ( const TrajectoryOptions options)

Definition at line 438 of file node.cc.

bool cartographer_ros::Node::ValidateTopicName ( const ::cartographer_ros_msgs::SensorTopics &  topics,
const TrajectoryOptions options 
)
private

Definition at line 382 of file node.cc.

bool cartographer_ros::Node::ValidateTrajectoryOptions ( const TrajectoryOptions options)
private

Definition at line 365 of file node.cc.

Member Data Documentation

std::unordered_map<int, ::ros::Subscriber> cartographer_ros::Node::imu_subscribers_
private

Definition at line 120 of file node.h.

std::unordered_map<int, ::ros::Subscriber> cartographer_ros::Node::laser_scan_subscribers_
private

Definition at line 117 of file node.h.

cartographer::common::Time cartographer_ros::Node::last_scan_matched_point_cloud_time_
private
Initial value:
=
cartographer::common::Time::min()

Definition at line 113 of file node.h.

std::unordered_map<int, ::ros::Subscriber> cartographer_ros::Node::multi_echo_laser_scan_subscribers_
private

Definition at line 118 of file node.h.

cartographer::common::Mutex cartographer_ros::Node::mutex_
private

Definition at line 104 of file node.h.

::ros::NodeHandle cartographer_ros::Node::node_handle_
private

Definition at line 107 of file node.h.

const NodeOptions cartographer_ros::Node::node_options_
private

Definition at line 100 of file node.h.

::ros::Publisher cartographer_ros::Node::occupancy_grid_publisher_
private

Definition at line 124 of file node.h.

std::thread cartographer_ros::Node::occupancy_grid_thread_
private

Definition at line 125 of file node.h.

std::unordered_map<int, ::ros::Subscriber> cartographer_ros::Node::odom_subscribers_
private

Definition at line 119 of file node.h.

std::unordered_map<int, std::vector<::ros::Subscriber> > cartographer_ros::Node::point_cloud_subscribers_
private

Definition at line 122 of file node.h.

::ros::Publisher cartographer_ros::Node::scan_matched_point_cloud_publisher_
private

Definition at line 112 of file node.h.

std::vector<::ros::ServiceServer> cartographer_ros::Node::service_servers_
private

Definition at line 111 of file node.h.

::ros::Publisher cartographer_ros::Node::submap_list_publisher_
private

Definition at line 108 of file node.h.

bool cartographer_ros::Node::terminating_ = false GUARDED_BY(mutex_)
private

Definition at line 126 of file node.h.

tf2_ros::TransformBroadcaster cartographer_ros::Node::tf_broadcaster_
private

Definition at line 102 of file node.h.

::ros::Publisher cartographer_ros::Node::trajectory_nodes_list_publisher_
private

Definition at line 109 of file node.h.

std::vector<::ros::WallTimer> cartographer_ros::Node::wall_timers_
private

Definition at line 130 of file node.h.


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


cartographer_ros
Author(s):
autogenerated on Mon Jun 10 2019 12:59:40