CGraphSlamHandler_ROS.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+
9  */
10 
11 #pragma once
12 
13 // ROS
14 #include <ros/ros.h>
15 #include <mrpt_msgs/GraphSlamStats.h>
16 #include <geometry_msgs/PoseStamped.h>
17 #include <geometry_msgs/PoseArray.h>
18 #include <geometry_msgs/TransformStamped.h>
19 #include <sensor_msgs/LaserScan.h>
20 #include <nav_msgs/Path.h>
21 #include <nav_msgs/Odometry.h>
22 #include <nav_msgs/OccupancyGrid.h>
23 #include <std_msgs/Header.h>
24 
27 #include <geometry_msgs/TransformStamped.h>
28 #include <tf2_ros/buffer.h>
32 #include <tf2/LinearMath/Vector3.h>
33 
34 // MRPT
35 #include <mrpt/graphs/CNetworkOfPoses.h>
36 #include <mrpt/maps/COccupancyGridMap2D.h>
37 #include <mrpt/obs/CObservationOdometry.h>
38 #include <mrpt/obs/CObservation2DRangeScan.h>
39 
40 #include <mrpt/system/string_utils.h>
41 #include <mrpt/system/filesystem.h>
42 #include <mrpt/system/os.h>
43 #include <mrpt/system/COutputLogger.h>
44 #include <mrpt/graphslam/apps_related/CGraphSlamHandler.h>
45 
49 
50 // cpp headers
51 #include <string>
52 #include <sstream>
53 #include <vector>
54 
55 namespace mrpt
56 {
57 namespace graphslam
58 {
59 namespace apps
60 {
64 template <class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
65 class CGraphSlamHandler_ROS : public CGraphSlamHandler<GRAPH_T>
66 {
67  public:
69  typedef typename GRAPH_T::constraint_t constraint_t;
71  typedef typename GRAPH_T::constraint_t::type_value pose_t;
72 
76  typedef CGraphSlamHandler<GRAPH_T> parent_t;
77 
79  mrpt::system::COutputLogger* logger,
80  TUserOptionsChecker<GRAPH_T>* options_checker, ros::NodeHandle* nh_in);
82 
83  void getParamsAsString(std::string* str_out);
84  std::string getParamsAsString();
85 
90  void readParams();
94  void printParams();
95 
104  void sniffOdom(const nav_msgs::Odometry::ConstPtr& ros_odom);
108  void sniffLaserScan(const sensor_msgs::LaserScan::ConstPtr& ros_laser_scan);
109  void sniffCameraImage();
111  void sniff3DPointCloud();
117  bool continueExec();
121  void generateReport();
141  void setupComm();
142 
150  void initEngine_ROS();
151  void initEngine_MR();
154  static const std::string sep_header;
155  static const std::string sep_subheader;
156 
157  private:
167  void processObservation(mrpt::obs::CObservation::Ptr& observ);
173  void _process(mrpt::obs::CObservation::Ptr& observ);
178  void readROSParameters();
179  void readStaticTFs();
185  void getROSParameters(std::string* str_out);
189  void verifyUserInput();
190 
194  void resetReceivedFlags();
202  void setupSubs();
203  void setupPubs();
204  void setupSrvs();
208 
209  // ROS server parameters
212  std::string m_node_reg;
213  std::string m_edge_reg;
214  std::string m_optimizer;
224  VerbosityLevel m_min_logging_level;
225 
245  mrpt::obs::CObservationOdometry::Ptr m_mrpt_odom;
246  mrpt::obs::CObservation2DRangeScan::Ptr m_mrpt_laser_scan;
258 
274  std::string m_odom_topic;
275  std::string m_laser_scan_topic;
276  std::string m_camera_topic;
277  std::string m_point_cloud_topic;
278 
283  std::string m_gridmap_topic;
284  std::string m_stats_topic;
301  std::string m_anchor_frame_id;
302  std::string m_base_link_frame_id;
303  std::string m_odom_frame_id;
311  geometry_msgs::TransformStamped m_anchor_odom_transform;
317  nav_msgs::Path m_odom_path;
318 
324 
328 
331 
333 
340 };
341 
342 } // namespace apps
343 } // namespace graphslam
344 } // namespace mrpt
345 
mrpt::graphslam::apps::CGraphSlamHandler_ROS::initEngine_MR
void initEngine_MR()
Definition: CGraphSlamHandler_ROS_impl.h:178
CGraphSlamEngine_ROS.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_stats_pub
ros::Publisher m_stats_pub
Definition: CGraphSlamHandler_ROS.h:266
mrpt::graphslam::apps::CGraphSlamHandler_ROS::~CGraphSlamHandler_ROS
~CGraphSlamHandler_ROS()
Definition: CGraphSlamHandler_ROS_impl.h:73
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_broadcaster
tf2_ros::TransformBroadcaster m_broadcaster
Definition: CGraphSlamHandler_ROS.h:291
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_odom_trajectory_topic
std::string m_odom_trajectory_topic
Definition: CGraphSlamHandler_ROS.h:282
CGraphSlamEngine_MR.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::verifyUserInput
void verifyUserInput()
Verify that the parameters read are valid and can be used with the CGraphSlamEngine_ROS instance.
Definition: CGraphSlamHandler_ROS_impl.h:270
ros::Publisher
mrpt::graphslam::apps::CGraphSlamHandler_ROS::readParams
void readParams()
Read the problem configuration parameters.
Definition: CGraphSlamHandler_ROS_impl.h:78
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_nh
ros::NodeHandle * m_nh
Pointer to the Ros NodeHanle instance.
Definition: CGraphSlamHandler_ROS.h:207
mrpt::graphslam::apps::CGraphSlamHandler_ROS::printParams
void printParams()
Print in a compact manner the overall problem configuration parameters.
Definition: CGraphSlamHandler_ROS_impl.h:262
mrpt::graphslam::apps::CGraphSlamHandler_ROS::parent_t
CGraphSlamHandler< GRAPH_T > parent_t
Handy parent type.
Definition: CGraphSlamHandler_ROS.h:76
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_curr_robot_pos_pub
ros::Publisher m_curr_robot_pos_pub
Definition: CGraphSlamHandler_ROS.h:259
mrpt::graphslam::apps::CGraphSlamHandler_ROS
Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper.
Definition: CGraphSlamHandler_ROS.h:65
ros.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::generateReport
void generateReport()
Generate the relevant report directory/files after the graphSLAM execution.
CGraphSlamHandler_ROS_impl.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_stats_pub_seq
int m_stats_pub_seq
Definition: CGraphSlamHandler_ROS.h:323
mrpt::graphslam::apps::CGraphSlamHandler_ROS::initEngine_ROS
void initEngine_ROS()
Initialize the CGraphslamEngine_* object.
Definition: CGraphSlamHandler_ROS_impl.h:163
mrpt::graphslam::apps::CGraphSlamHandler_ROS::sniffCameraImage
void sniffCameraImage()
Definition: CGraphSlamHandler_ROS_impl.h:712
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_edge_reg
std::string m_edge_reg
Definition: CGraphSlamHandler_ROS.h:213
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_input_odometry_offset
pose_t m_input_odometry_offset
Definition: CGraphSlamHandler_ROS.h:339
buffer.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::_process
void _process(mrpt::obs::CObservation::Ptr &observ)
Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method.
Definition: CGraphSlamHandler_ROS_impl.h:732
Vector3.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::sniff3DPointCloud
void sniff3DPointCloud()
Definition: CGraphSlamHandler_ROS_impl.h:717
mrpt
Definition: CConnectionManager.h:31
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_odom_path
nav_msgs::Path m_odom_path
Odometry path of the robot. Handy mostly for visualization reasons.
Definition: CGraphSlamHandler_ROS.h:317
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_queue_size
int m_queue_size
ROS topic publisher standard queue size.
Definition: CGraphSlamHandler_ROS.h:330
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_robot_tr_poses_topic
std::string m_robot_tr_poses_topic
Definition: CGraphSlamHandler_ROS.h:281
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_first_time_in_sniff_odom
bool m_first_time_in_sniff_odom
Initial offset of the received odometry.
Definition: CGraphSlamHandler_ROS.h:338
transform_broadcaster.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_pub_seq
int m_pub_seq
Times a messge has been published => usePublishersBroadcasters method is called.
Definition: CGraphSlamHandler_ROS.h:322
mrpt::graphslam::apps::CGraphSlamHandler_ROS::CGraphSlamHandler_ROS
CGraphSlamHandler_ROS(mrpt::system::COutputLogger *logger, TUserOptionsChecker< GRAPH_T > *options_checker, ros::NodeHandle *nh_in)
Definition: CGraphSlamHandler_ROS_impl.h:41
mrpt::graphslam::apps::CGraphSlamHandler_ROS::readStaticTFs
void readStaticTFs()
Definition: CGraphSlamHandler_ROS_impl.h:158
mrpt::graphslam::apps::CGraphSlamHandler_ROS::self_t
CGraphSlamHandler_ROS< GRAPH_T > self_t
Handy self type.
Definition: CGraphSlamHandler_ROS.h:74
rename_rviz_topics.logger
logger
Definition: rename_rviz_topics.py:31
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_camera_topic
std::string m_camera_topic
Definition: CGraphSlamHandler_ROS.h:276
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_received_laser_scan
bool m_received_laser_scan
Definition: CGraphSlamHandler_ROS.h:233
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_gridmap_pub
ros::Publisher m_gridmap_pub
Definition: CGraphSlamHandler_ROS.h:265
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_point_cloud_scan_sub
ros::Subscriber m_point_cloud_scan_sub
Definition: CGraphSlamHandler_ROS.h:257
mrpt::graphslam::apps::CGraphSlamHandler_ROS::sniffOdom
void sniffOdom(const nav_msgs::Odometry::ConstPtr &ros_odom)
Callback method for handling incoming odometry measurements in a ROS topic.
Definition: CGraphSlamHandler_ROS_impl.h:637
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_min_logging_level
VerbosityLevel m_min_logging_level
Minimum logging level for the current class instance.
Definition: CGraphSlamHandler_ROS.h:224
mrpt::graphslam::apps::CGraphSlamHandler_ROS::setupPubs
void setupPubs()
Definition: CGraphSlamHandler_ROS_impl.h:379
mrpt::graphslam::apps::CGraphSlamHandler_ROS::continueExec
bool continueExec()
Indicate whether graphslam execution can proceed normally.
Quaternion.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_received_camera
bool m_received_camera
Definition: CGraphSlamHandler_ROS.h:234
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_gridmap_topic
std::string m_gridmap_topic
Definition: CGraphSlamHandler_ROS.h:283
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_optimizer
std::string m_optimizer
Definition: CGraphSlamHandler_ROS.h:214
mrpt::graphslam::apps::CGraphSlamHandler_ROS::processObservation
void processObservation(mrpt::obs::CObservation::Ptr &observ)
Process an incoming measurement.
Definition: CGraphSlamHandler_ROS_impl.h:722
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_graph_nodes_last_size
size_t m_graph_nodes_last_size
Definition: CGraphSlamHandler_ROS.h:332
tf2_ros::Buffer
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_mrpt_odom
mrpt::obs::CObservationOdometry::Ptr m_mrpt_odom
Received laser scan - converted into MRPT CObservation* format.
Definition: CGraphSlamHandler_ROS.h:245
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_laser_scan_sub
ros::Subscriber m_laser_scan_sub
Definition: CGraphSlamHandler_ROS.h:255
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_received_point_cloud
bool m_received_point_cloud
Definition: CGraphSlamHandler_ROS.h:235
mrpt::graphslam::apps::CGraphSlamHandler_ROS::resetReceivedFlags
void resetReceivedFlags()
Reset the flags indicating whether we have received new data (odometry, laser scans etc....
Definition: CGraphSlamHandler_ROS_impl.h:746
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_robot_trajectory_pub
ros::Publisher m_robot_trajectory_pub
Definition: CGraphSlamHandler_ROS.h:260
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_node_reg
std::string m_node_reg
Definition: CGraphSlamHandler_ROS.h:212
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_base_link_frame_id
std::string m_base_link_frame_id
Definition: CGraphSlamHandler_ROS.h:302
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_point_cloud_topic
std::string m_point_cloud_topic
Definition: CGraphSlamHandler_ROS.h:277
mrpt::graphslam::apps::CGraphSlamHandler_ROS::usePublishersBroadcasters
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
Definition: CGraphSlamHandler_ROS_impl.h:432
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_buffer
tf2_ros::Buffer m_buffer
Definition: CGraphSlamHandler_ROS.h:290
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_odom_sub
ros::Subscriber m_odom_sub
Definition: CGraphSlamHandler_ROS.h:254
transform_listener.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_odom_trajectory_pub
ros::Publisher m_odom_trajectory_pub
Definition: CGraphSlamHandler_ROS.h:264
mrpt::graphslam::apps::CGraphSlamHandler_ROS::sep_header
static const std::string sep_header
Definition: CGraphSlamHandler_ROS.h:154
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_mrpt_laser_scan
mrpt::obs::CObservation2DRangeScan::Ptr m_mrpt_laser_scan
Definition: CGraphSlamHandler_ROS.h:246
mrpt::graphslam::apps::CGraphSlamHandler_ROS::constraint_t
GRAPH_T::constraint_t constraint_t
type of graph constraints
Definition: CGraphSlamHandler_ROS.h:69
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_stats_topic
std::string m_stats_topic
Definition: CGraphSlamHandler_ROS.h:284
TUserOptionsChecker_ROS.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_laser_scan_topic
std::string m_laser_scan_topic
Definition: CGraphSlamHandler_ROS.h:275
mrpt::graphslam::apps::CGraphSlamHandler_ROS::getParamsAsString
std::string getParamsAsString()
Definition: CGraphSlamHandler_ROS_impl.h:254
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_camera_scan_sub
ros::Subscriber m_camera_scan_sub
Definition: CGraphSlamHandler_ROS.h:256
tf2_ros::TransformBroadcaster
mrpt::graphslam::apps::CGraphSlamHandler_ROS::sep_subheader
static const std::string sep_subheader
Definition: CGraphSlamHandler_ROS.h:155
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_odom_topic
std::string m_odom_topic
Definition: CGraphSlamHandler_ROS.h:274
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_gt_trajectory_pub
ros::Publisher m_gt_trajectory_pub
Definition: CGraphSlamHandler_ROS.h:262
mrpt::graphslam::apps::CGraphSlamHandler_ROS::readROSParameters
void readROSParameters()
read configuration parameters from the ROS parameter server.
Definition: CGraphSlamHandler_ROS_impl.h:87
tf2_geometry_msgs.h
mrpt::graphslam::apps::CGraphSlamHandler_ROS::setupComm
void setupComm()
Wrapper method around the protected setup* class methods.
Definition: CGraphSlamHandler_ROS_impl.h:335
mrpt::graphslam::apps::CGraphSlamHandler_ROS::sniffLaserScan
void sniffLaserScan(const sensor_msgs::LaserScan::ConstPtr &ros_laser_scan)
Callback method for handling incoming LaserScans objects in a ROS topic.
Definition: CGraphSlamHandler_ROS_impl.h:614
mrpt::graphslam::apps::CGraphSlamHandler_ROS::getROSParameters
void getROSParameters(std::string *str_out)
Fill in the given string with the parameters that have been read from the ROS parameter server.
Definition: CGraphSlamHandler_ROS_impl.h:197
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_measurement_cnt
size_t m_measurement_cnt
Total counter of the processed measurements.
Definition: CGraphSlamHandler_ROS.h:327
mrpt::graphslam::apps::CGraphSlamHandler_ROS::setupSubs
void setupSubs()
Definition: CGraphSlamHandler_ROS_impl.h:352
mrpt::graphslam::apps::CGraphSlamHandler_ROS::pose_t
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
Definition: CGraphSlamHandler_ROS.h:71
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_robot_trajectory_topic
std::string m_robot_trajectory_topic
Definition: CGraphSlamHandler_ROS.h:280
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_received_odom
bool m_received_odom
Definition: CGraphSlamHandler_ROS.h:232
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_curr_robot_pos_topic
std::string m_curr_robot_pos_topic
Definition: CGraphSlamHandler_ROS.h:279
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_SLAM_eval_metric_pub
ros::Publisher m_SLAM_eval_metric_pub
Definition: CGraphSlamHandler_ROS.h:263
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_robot_tr_poses_pub
ros::Publisher m_robot_tr_poses_pub
Definition: CGraphSlamHandler_ROS.h:261
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_odom_frame_id
std::string m_odom_frame_id
Definition: CGraphSlamHandler_ROS.h:303
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_anchor_odom_transform
geometry_msgs::TransformStamped m_anchor_odom_transform
Definition: CGraphSlamHandler_ROS.h:311
ros::NodeHandle
ros::Subscriber
mrpt::graphslam::apps::CGraphSlamHandler_ROS::m_anchor_frame_id
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.
Definition: CGraphSlamHandler_ROS.h:301
mrpt::graphslam::apps::CGraphSlamHandler_ROS::setupSrvs
void setupSrvs()
Definition: CGraphSlamHandler_ROS_impl.h:423


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