Public Types | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T > Class Template Reference

Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper. More...

#include <CGraphSlamHandler_ROS.h>

Inheritance diagram for mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >:
Inheritance graph
[legend]

Public Types

typedef GRAPH_T::constraint_t constraint_t
 type of graph constraints More...
 
typedef CGraphSlamHandler< GRAPH_T > parent_t
 Handy parent type. More...
 
typedef GRAPH_T::constraint_t::type_value pose_t
 type of underlying poses (2D/3D). More...
 
typedef CGraphSlamHandler_ROS< GRAPH_T > self_t
 Handy self type. More...
 

Public Member Functions

 CGraphSlamHandler_ROS (mrpt::system::COutputLogger *logger, TUserOptionsChecker< GRAPH_T > *options_checker, ros::NodeHandle *nh_in)
 
bool continueExec ()
 Indicate whether graphslam execution can proceed normally. More...
 
void generateReport ()
 Generate the relevant report directory/files after the graphSLAM execution. More...
 
std::string getParamsAsString ()
 
void getParamsAsString (std::string *str_out)
 
void printParams ()
 Print in a compact manner the overall problem configuration parameters. More...
 
void readParams ()
 Read the problem configuration parameters. More...
 
void setupComm ()
 Wrapper method around the protected setup* class methods. More...
 
bool usePublishersBroadcasters ()
 Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using the tf2_ros::TransformBroadcaster. More...
 
 ~CGraphSlamHandler_ROS ()
 
Sniffing methods

Sniff measurements off their corresponding topics

void sniffOdom (const nav_msgs::Odometry::ConstPtr &ros_odom)
 Callback method for handling incoming odometry measurements in a ROS topic. More...
 
void sniffLaserScan (const sensor_msgs::LaserScan::ConstPtr &ros_laser_scan)
 Callback method for handling incoming LaserScans objects in a ROS topic. More...
 
void sniffCameraImage ()
 
void sniff3DPointCloud ()
 
void initEngine_ROS ()
 Initialize the CGraphslamEngine_* object. More...
 
void initEngine_MR ()
 

Static Public Attributes

static const std::string sep_header
 
static const std::string sep_subheader
 

Private Member Functions

void _process (mrpt::obs::CObservation::Ptr &observ)
 Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method. More...
 
void getROSParameters (std::string *str_out)
 Fill in the given string with the parameters that have been read from the ROS parameter server. More...
 
void processObservation (mrpt::obs::CObservation::Ptr &observ)
 Process an incoming measurement. More...
 
void readROSParameters ()
 read configuration parameters from the ROS parameter server. More...
 
void readStaticTFs ()
 
void resetReceivedFlags ()
 Reset the flags indicating whether we have received new data (odometry, laser scans etc.) More...
 
void verifyUserInput ()
 Verify that the parameters read are valid and can be used with the CGraphSlamEngine_ROS instance. More...
 
setup* ROS-related methods

Methods for setting up topic subscribers, publishers, and corresponding services

See also
setupComm
void setupSubs ()
 
void setupPubs ()
 
void setupSrvs ()
 

Private Attributes

bool m_first_time_in_sniff_odom
 Initial offset of the received odometry. More...
 
size_t m_graph_nodes_last_size
 
pose_t m_input_odometry_offset
 
size_t m_measurement_cnt
 Total counter of the processed measurements. More...
 
VerbosityLevel m_min_logging_level
 Minimum logging level for the current class instance. More...
 
ros::NodeHandlem_nh
 Pointer to the Ros NodeHanle instance. More...
 
nav_msgs::Path m_odom_path
 Odometry path of the robot. Handy mostly for visualization reasons. More...
 
int m_pub_seq
 Times a messge has been published => usePublishersBroadcasters method is called. More...
 
int m_queue_size
 ROS topic publisher standard queue size. More...
 
int m_stats_pub_seq
 
node, edge, optimizer modules in string representation
std::string m_node_reg
 
std::string m_edge_reg
 
std::string m_optimizer
 
Received measurements - boolean flags

Flags that indicate if any new measurements have arrived in the corresponding topics.

bool m_received_odom
 
bool m_received_laser_scan
 
bool m_received_camera
 
bool m_received_point_cloud
 
Processed measurements

Measurements that the class can the class instance is keeping track of and passes to the CGraphSlamEngine_ROS instance.

mrpt::obs::CObservationOdometry::Ptr m_mrpt_odom
 Received laser scan - converted into MRPT CObservation* format. More...
 
mrpt::obs::CObservation2DRangeScan::Ptr m_mrpt_laser_scan
 
Subscribers - Publishers

ROS Topic Subscriber/Publisher instances

ros::Subscriber m_odom_sub
 
ros::Subscriber m_laser_scan_sub
 
ros::Subscriber m_camera_scan_sub
 
ros::Subscriber m_point_cloud_scan_sub
 
ros::Publisher m_curr_robot_pos_pub
 
ros::Publisher m_robot_trajectory_pub
 
ros::Publisher m_robot_tr_poses_pub
 
ros::Publisher m_gt_trajectory_pub
 
ros::Publisher m_SLAM_eval_metric_pub
 
ros::Publisher m_odom_trajectory_pub
 
ros::Publisher m_gridmap_pub
 
ros::Publisher m_stats_pub
 
Topic Names

Names of the topics that the class instance subscribes or publishes to

std::string m_odom_topic
 
std::string m_laser_scan_topic
 
std::string m_camera_topic
 
std::string m_point_cloud_topic
 
std::string m_curr_robot_pos_topic
 
std::string m_robot_trajectory_topic
 
std::string m_robot_tr_poses_topic
 
std::string m_odom_trajectory_topic
 
std::string m_gridmap_topic
 
std::string m_stats_topic
 
TransformBroadcasters - TransformListeners
tf2_ros::Buffer m_buffer
 
tf2_ros::TransformBroadcaster m_broadcaster
 
TF Frame IDs

Names of the current TF Frames available

std::string m_anchor_frame_id
 Frame that the robot starts from. In a single-robot SLAM setup this can be set to the world frame. More...
 
std::string m_base_link_frame_id
 
std::string m_odom_frame_id
 
Geometrical Configuration

Variables that setup the geometrical dimensions, distances between the different robot parts etc.

geometry_msgs::TransformStamped m_anchor_odom_transform
 

Detailed Description

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
class mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >

Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper.

Definition at line 65 of file CGraphSlamHandler_ROS.h.

Member Typedef Documentation

◆ constraint_t

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
typedef GRAPH_T::constraint_t mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::constraint_t

type of graph constraints

Definition at line 69 of file CGraphSlamHandler_ROS.h.

◆ parent_t

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
typedef CGraphSlamHandler<GRAPH_T> mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::parent_t

Handy parent type.

Definition at line 76 of file CGraphSlamHandler_ROS.h.

◆ pose_t

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
typedef GRAPH_T::constraint_t::type_value mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::pose_t

type of underlying poses (2D/3D).

Definition at line 71 of file CGraphSlamHandler_ROS.h.

◆ self_t

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
typedef CGraphSlamHandler_ROS<GRAPH_T> mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::self_t

Handy self type.

Definition at line 74 of file CGraphSlamHandler_ROS.h.

Constructor & Destructor Documentation

◆ CGraphSlamHandler_ROS()

template<class GRAPH_T >
mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::CGraphSlamHandler_ROS ( mrpt::system::COutputLogger *  logger,
TUserOptionsChecker< GRAPH_T > *  options_checker,
ros::NodeHandle nh_in 
)

Definition at line 41 of file CGraphSlamHandler_ROS_impl.h.

◆ ~CGraphSlamHandler_ROS()

Definition at line 73 of file CGraphSlamHandler_ROS_impl.h.

Member Function Documentation

◆ _process()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::_process ( mrpt::obs::CObservation::Ptr &  observ)
private

Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method.

See also
processObservation();

Definition at line 732 of file CGraphSlamHandler_ROS_impl.h.

◆ continueExec()

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::continueExec ( )

Indicate whether graphslam execution can proceed normally.

Returns
False if user has demanded to exit (pressed <C-c>), True otherwise

◆ generateReport()

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::generateReport ( )

Generate the relevant report directory/files after the graphSLAM execution.

◆ getParamsAsString() [1/2]

template<class GRAPH_T >
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::getParamsAsString

Definition at line 254 of file CGraphSlamHandler_ROS_impl.h.

◆ getParamsAsString() [2/2]

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::getParamsAsString ( std::string *  str_out)

Definition at line 236 of file CGraphSlamHandler_ROS_impl.h.

◆ getROSParameters()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::getROSParameters ( std::string *  str_out)
private

Fill in the given string with the parameters that have been read from the ROS parameter server.

See also
getParamsAsString, readROSParameters

Definition at line 197 of file CGraphSlamHandler_ROS_impl.h.

◆ initEngine_MR()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::initEngine_MR

Definition at line 178 of file CGraphSlamHandler_ROS_impl.h.

◆ initEngine_ROS()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::initEngine_ROS

Initialize the CGraphslamEngine_* object.

The CGraphSlamEngine instance is to be instaniated depending on the user application at hand. User should call this method just after reading the problem parameters.

Definition at line 163 of file CGraphSlamHandler_ROS_impl.h.

◆ printParams()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::printParams

Print in a compact manner the overall problem configuration parameters.

Definition at line 262 of file CGraphSlamHandler_ROS_impl.h.

◆ processObservation()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::processObservation ( mrpt::obs::CObservation::Ptr &  observ)
private

Process an incoming measurement.

Method is a wrapper around the _process method

Note
Method is automatically called when a new measurement is fetched from a subscribed topic
See also
_process

Definition at line 722 of file CGraphSlamHandler_ROS_impl.h.

◆ readParams()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::readParams

Read the problem configuration parameters.

See also
readROSParameters, printParams

Definition at line 78 of file CGraphSlamHandler_ROS_impl.h.

◆ readROSParameters()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::readROSParameters
private

read configuration parameters from the ROS parameter server.

See also
readParams

Definition at line 87 of file CGraphSlamHandler_ROS_impl.h.

◆ readStaticTFs()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::readStaticTFs
private

Definition at line 158 of file CGraphSlamHandler_ROS_impl.h.

◆ resetReceivedFlags()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::resetReceivedFlags
private

Reset the flags indicating whether we have received new data (odometry, laser scans etc.)

Definition at line 746 of file CGraphSlamHandler_ROS_impl.h.

◆ setupComm()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::setupComm

Wrapper method around the protected setup* class methods.

Handy for setting up publishers, subscribers, services, TF-related stuff all at once from the user application

Note
method should be called right after the call to CGraphSlamHandler_ROS::readParams method

Definition at line 335 of file CGraphSlamHandler_ROS_impl.h.

◆ setupPubs()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::setupPubs
private

Definition at line 379 of file CGraphSlamHandler_ROS_impl.h.

◆ setupSrvs()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::setupSrvs
private

Definition at line 423 of file CGraphSlamHandler_ROS_impl.h.

◆ setupSubs()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::setupSubs
private

Definition at line 352 of file CGraphSlamHandler_ROS_impl.h.

◆ sniff3DPointCloud()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sniff3DPointCloud

TODO - Implement this

Definition at line 717 of file CGraphSlamHandler_ROS_impl.h.

◆ sniffCameraImage()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sniffCameraImage

Definition at line 712 of file CGraphSlamHandler_ROS_impl.h.

◆ sniffLaserScan()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sniffLaserScan ( const sensor_msgs::LaserScan::ConstPtr &  ros_laser_scan)

Callback method for handling incoming LaserScans objects in a ROS topic.

Definition at line 614 of file CGraphSlamHandler_ROS_impl.h.

◆ sniffOdom()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sniffOdom ( const nav_msgs::Odometry::ConstPtr &  ros_odom)

Callback method for handling incoming odometry measurements in a ROS topic.

Definition at line 637 of file CGraphSlamHandler_ROS_impl.h.

◆ usePublishersBroadcasters()

template<class GRAPH_T >
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::usePublishersBroadcasters

Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using the tf2_ros::TransformBroadcaster.

Method makes the necessary calls to all the publishers of the class and broadcaster instances

See also
continueExec
Returns
True if the graphSLAM execution is to continue normally, false otherwise

Definition at line 432 of file CGraphSlamHandler_ROS_impl.h.

◆ verifyUserInput()

template<class GRAPH_T >
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::verifyUserInput
private

Verify that the parameters read are valid and can be used with the CGraphSlamEngine_ROS instance.

Definition at line 270 of file CGraphSlamHandler_ROS_impl.h.

Member Data Documentation

◆ m_anchor_frame_id

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_anchor_frame_id
private

Frame that the robot starts from. In a single-robot SLAM setup this can be set to the world frame.

Definition at line 301 of file CGraphSlamHandler_ROS.h.

◆ m_anchor_odom_transform

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
geometry_msgs::TransformStamped mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_anchor_odom_transform
private

Definition at line 311 of file CGraphSlamHandler_ROS.h.

◆ m_base_link_frame_id

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_base_link_frame_id
private

Definition at line 302 of file CGraphSlamHandler_ROS.h.

◆ m_broadcaster

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
tf2_ros::TransformBroadcaster mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_broadcaster
private

Definition at line 291 of file CGraphSlamHandler_ROS.h.

◆ m_buffer

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
tf2_ros::Buffer mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_buffer
private

Definition at line 290 of file CGraphSlamHandler_ROS.h.

◆ m_camera_scan_sub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Subscriber mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_camera_scan_sub
private

Definition at line 256 of file CGraphSlamHandler_ROS.h.

◆ m_camera_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_camera_topic
private

Definition at line 276 of file CGraphSlamHandler_ROS.h.

◆ m_curr_robot_pos_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_curr_robot_pos_pub
private

Definition at line 259 of file CGraphSlamHandler_ROS.h.

◆ m_curr_robot_pos_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_curr_robot_pos_topic
private

Definition at line 279 of file CGraphSlamHandler_ROS.h.

◆ m_edge_reg

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_edge_reg
private

Definition at line 213 of file CGraphSlamHandler_ROS.h.

◆ m_first_time_in_sniff_odom

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_first_time_in_sniff_odom
private

Initial offset of the received odometry.

Assumption is that in the beginning I have 0 position, thus the incoming odometry for the algorithm has to be 0

Definition at line 338 of file CGraphSlamHandler_ROS.h.

◆ m_graph_nodes_last_size

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
size_t mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_graph_nodes_last_size
private

Definition at line 332 of file CGraphSlamHandler_ROS.h.

◆ m_gridmap_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_gridmap_pub
private

Definition at line 265 of file CGraphSlamHandler_ROS.h.

◆ m_gridmap_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_gridmap_topic
private

Definition at line 283 of file CGraphSlamHandler_ROS.h.

◆ m_gt_trajectory_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_gt_trajectory_pub
private

Definition at line 262 of file CGraphSlamHandler_ROS.h.

◆ m_input_odometry_offset

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
pose_t mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_input_odometry_offset
private

Definition at line 339 of file CGraphSlamHandler_ROS.h.

◆ m_laser_scan_sub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Subscriber mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_laser_scan_sub
private

Definition at line 255 of file CGraphSlamHandler_ROS.h.

◆ m_laser_scan_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_laser_scan_topic
private

Definition at line 275 of file CGraphSlamHandler_ROS.h.

◆ m_measurement_cnt

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
size_t mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_measurement_cnt
private

Total counter of the processed measurements.

Definition at line 327 of file CGraphSlamHandler_ROS.h.

◆ m_min_logging_level

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
VerbosityLevel mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_min_logging_level
private

Minimum logging level for the current class instance.

This doesn't affect the logging level of CGraphSlamEngine or any of the deciders/optimizers.

Note
Value is fetched from the ROS Parameter Server (not from the external .ini file.

Definition at line 224 of file CGraphSlamHandler_ROS.h.

◆ m_mrpt_laser_scan

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::obs::CObservation2DRangeScan::Ptr mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_mrpt_laser_scan
private

Definition at line 246 of file CGraphSlamHandler_ROS.h.

◆ m_mrpt_odom

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::obs::CObservationOdometry::Ptr mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_mrpt_odom
private

Received laser scan - converted into MRPT CObservation* format.

Definition at line 245 of file CGraphSlamHandler_ROS.h.

◆ m_nh

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::NodeHandle* mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_nh
private

Pointer to the Ros NodeHanle instance.

Definition at line 207 of file CGraphSlamHandler_ROS.h.

◆ m_node_reg

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_node_reg
private

Definition at line 212 of file CGraphSlamHandler_ROS.h.

◆ m_odom_frame_id

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_odom_frame_id
private

Definition at line 303 of file CGraphSlamHandler_ROS.h.

◆ m_odom_path

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
nav_msgs::Path mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_odom_path
private

Odometry path of the robot. Handy mostly for visualization reasons.

Definition at line 317 of file CGraphSlamHandler_ROS.h.

◆ m_odom_sub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Subscriber mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_odom_sub
private

Definition at line 254 of file CGraphSlamHandler_ROS.h.

◆ m_odom_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_odom_topic
private

Definition at line 274 of file CGraphSlamHandler_ROS.h.

◆ m_odom_trajectory_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_odom_trajectory_pub
private

Definition at line 264 of file CGraphSlamHandler_ROS.h.

◆ m_odom_trajectory_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_odom_trajectory_topic
private

Definition at line 282 of file CGraphSlamHandler_ROS.h.

◆ m_optimizer

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_optimizer
private

Definition at line 214 of file CGraphSlamHandler_ROS.h.

◆ m_point_cloud_scan_sub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Subscriber mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_point_cloud_scan_sub
private

Definition at line 257 of file CGraphSlamHandler_ROS.h.

◆ m_point_cloud_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_point_cloud_topic
private

Definition at line 277 of file CGraphSlamHandler_ROS.h.

◆ m_pub_seq

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_pub_seq
private

Times a messge has been published => usePublishersBroadcasters method is called.

Definition at line 322 of file CGraphSlamHandler_ROS.h.

◆ m_queue_size

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_queue_size
private

ROS topic publisher standard queue size.

Definition at line 330 of file CGraphSlamHandler_ROS.h.

◆ m_received_camera

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_received_camera
private

Definition at line 234 of file CGraphSlamHandler_ROS.h.

◆ m_received_laser_scan

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_received_laser_scan
private

Definition at line 233 of file CGraphSlamHandler_ROS.h.

◆ m_received_odom

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_received_odom
private

Definition at line 232 of file CGraphSlamHandler_ROS.h.

◆ m_received_point_cloud

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_received_point_cloud
private

Definition at line 235 of file CGraphSlamHandler_ROS.h.

◆ m_robot_tr_poses_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_robot_tr_poses_pub
private

Definition at line 261 of file CGraphSlamHandler_ROS.h.

◆ m_robot_tr_poses_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_robot_tr_poses_topic
private

Definition at line 281 of file CGraphSlamHandler_ROS.h.

◆ m_robot_trajectory_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_robot_trajectory_pub
private

Definition at line 260 of file CGraphSlamHandler_ROS.h.

◆ m_robot_trajectory_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_robot_trajectory_topic
private

Definition at line 280 of file CGraphSlamHandler_ROS.h.

◆ m_SLAM_eval_metric_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_SLAM_eval_metric_pub
private

Definition at line 263 of file CGraphSlamHandler_ROS.h.

◆ m_stats_pub

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
ros::Publisher mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_stats_pub
private

Definition at line 266 of file CGraphSlamHandler_ROS.h.

◆ m_stats_pub_seq

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_stats_pub_seq
private

Definition at line 323 of file CGraphSlamHandler_ROS.h.

◆ m_stats_topic

template<class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::m_stats_topic
private

Definition at line 284 of file CGraphSlamHandler_ROS.h.

◆ sep_header

template<class GRAPH_T >
const std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sep_header
static

Definition at line 154 of file CGraphSlamHandler_ROS.h.

◆ sep_subheader

template<class GRAPH_T >
const std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sep_subheader
static

Definition at line 155 of file CGraphSlamHandler_ROS.h.


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


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Sep 19 2024 02:26:31