Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper. More...
#include <CGraphSlamHandler_ROS.h>
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
| |
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::NodeHandle * | m_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 |
Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper.
Definition at line 65 of file CGraphSlamHandler_ROS.h.
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.
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.
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.
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.
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.
mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::~CGraphSlamHandler_ROS |
Definition at line 73 of file CGraphSlamHandler_ROS_impl.h.
|
private |
Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method.
Definition at line 732 of file CGraphSlamHandler_ROS_impl.h.
bool mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::continueExec | ( | ) |
Indicate whether graphslam execution can proceed normally.
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::generateReport | ( | ) |
Generate the relevant report directory/files after the graphSLAM execution.
std::string mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::getParamsAsString |
Definition at line 254 of file CGraphSlamHandler_ROS_impl.h.
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::getParamsAsString | ( | std::string * | str_out | ) |
Definition at line 236 of file CGraphSlamHandler_ROS_impl.h.
|
private |
Fill in the given string with the parameters that have been read from the ROS parameter server.
Definition at line 197 of file CGraphSlamHandler_ROS_impl.h.
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::initEngine_MR |
Definition at line 178 of file CGraphSlamHandler_ROS_impl.h.
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.
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.
|
private |
Process an incoming measurement.
Method is a wrapper around the _process method
Definition at line 722 of file CGraphSlamHandler_ROS_impl.h.
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::readParams |
Read the problem configuration parameters.
Definition at line 78 of file CGraphSlamHandler_ROS_impl.h.
|
private |
read configuration parameters from the ROS parameter server.
Definition at line 87 of file CGraphSlamHandler_ROS_impl.h.
|
private |
Definition at line 158 of file CGraphSlamHandler_ROS_impl.h.
|
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.
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
Definition at line 335 of file CGraphSlamHandler_ROS_impl.h.
|
private |
Definition at line 379 of file CGraphSlamHandler_ROS_impl.h.
|
private |
Definition at line 423 of file CGraphSlamHandler_ROS_impl.h.
|
private |
Definition at line 352 of file CGraphSlamHandler_ROS_impl.h.
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sniff3DPointCloud |
TODO - Implement this
Definition at line 717 of file CGraphSlamHandler_ROS_impl.h.
void mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T >::sniffCameraImage |
Definition at line 712 of file CGraphSlamHandler_ROS_impl.h.
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.
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.
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
Definition at line 432 of file CGraphSlamHandler_ROS_impl.h.
|
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.
|
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.
|
private |
Definition at line 311 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 302 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 291 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 290 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 256 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 276 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 259 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 279 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 213 of file CGraphSlamHandler_ROS.h.
|
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.
|
private |
Definition at line 332 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 265 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 283 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 262 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 339 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 255 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 275 of file CGraphSlamHandler_ROS.h.
|
private |
Total counter of the processed measurements.
Definition at line 327 of file CGraphSlamHandler_ROS.h.
|
private |
Minimum logging level for the current class instance.
This doesn't affect the logging level of CGraphSlamEngine or any of the deciders/optimizers.
Definition at line 224 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 246 of file CGraphSlamHandler_ROS.h.
|
private |
Received laser scan - converted into MRPT CObservation* format.
Definition at line 245 of file CGraphSlamHandler_ROS.h.
|
private |
Pointer to the Ros NodeHanle instance.
Definition at line 207 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 212 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 303 of file CGraphSlamHandler_ROS.h.
|
private |
Odometry path of the robot. Handy mostly for visualization reasons.
Definition at line 317 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 254 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 274 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 264 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 282 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 214 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 257 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 277 of file CGraphSlamHandler_ROS.h.
|
private |
Times a messge has been published => usePublishersBroadcasters method is called.
Definition at line 322 of file CGraphSlamHandler_ROS.h.
|
private |
ROS topic publisher standard queue size.
Definition at line 330 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 234 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 233 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 232 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 235 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 261 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 281 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 260 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 280 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 263 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 266 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 323 of file CGraphSlamHandler_ROS.h.
|
private |
Definition at line 284 of file CGraphSlamHandler_ROS.h.
|
static |
Definition at line 154 of file CGraphSlamHandler_ROS.h.
|
static |
Definition at line 155 of file CGraphSlamHandler_ROS.h.