#include <node.h>
Public Member Functions | |
void | FinishAllTrajectories () |
MapBuilderBridge * | map_builder_bridge () |
Node (const NodeOptions &node_options, tf2_ros::Buffer *tf_buffer) | |
Node (const Node &)=delete | |
::ros::NodeHandle * | node_handle () |
Node & | operator= (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::Subscriber > | imu_subscribers_ |
std::unordered_map< int,::ros::Subscriber > | laser_scan_subscribers_ |
cartographer::common::Time | last_scan_matched_point_cloud_time_ |
std::unordered_map< int,::ros::Subscriber > | multi_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::Subscriber > | odom_subscribers_ |
std::unordered_map< int, std::vector<::ros::Subscriber > > | point_cloud_subscribers_ |
::ros::Publisher | scan_matched_point_cloud_publisher_ |
std::vector<::ros::ServiceServer > | service_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::WallTimer > | wall_timers_ |
cartographer_ros::Node::Node | ( | const NodeOptions & | node_options, |
tf2_ros::Buffer * | tf_buffer | ||
) |
|
delete |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
MapBuilderBridge * cartographer_ros::Node::map_builder_bridge | ( | ) |
ros::NodeHandle * cartographer_ros::Node::node_handle | ( | ) |
|
private |
|
private |
|
private |
|
private |
void cartographer_ros::Node::StartTrajectoryWithDefaultTopics | ( | const TrajectoryOptions & | options | ) |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |