Go to the documentation of this file.
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>
27 #include <geometry_msgs/TransformStamped.h>
35 #include <mrpt/graphs/CNetworkOfPoses.h>
36 #include <mrpt/maps/COccupancyGridMap2D.h>
37 #include <mrpt/obs/CObservationOdometry.h>
38 #include <mrpt/obs/CObservation2DRangeScan.h>
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>
64 template <
class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
71 typedef typename GRAPH_T::constraint_t::type_value
pose_t;
79 mrpt::system::COutputLogger*
logger,
104 void sniffOdom(
const nav_msgs::Odometry::ConstPtr& ros_odom);
108 void sniffLaserScan(
const sensor_msgs::LaserScan::ConstPtr& ros_laser_scan);
173 void _process(mrpt::obs::CObservation::Ptr& observ);
ros::Publisher m_stats_pub
tf2_ros::TransformBroadcaster m_broadcaster
std::string m_odom_trajectory_topic
void verifyUserInput()
Verify that the parameters read are valid and can be used with the CGraphSlamEngine_ROS instance.
void readParams()
Read the problem configuration parameters.
ros::NodeHandle * m_nh
Pointer to the Ros NodeHanle instance.
void printParams()
Print in a compact manner the overall problem configuration parameters.
CGraphSlamHandler< GRAPH_T > parent_t
Handy parent type.
ros::Publisher m_curr_robot_pos_pub
Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper.
void generateReport()
Generate the relevant report directory/files after the graphSLAM execution.
void initEngine_ROS()
Initialize the CGraphslamEngine_* object.
pose_t m_input_odometry_offset
void _process(mrpt::obs::CObservation::Ptr &observ)
Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method.
nav_msgs::Path m_odom_path
Odometry path of the robot. Handy mostly for visualization reasons.
int m_queue_size
ROS topic publisher standard queue size.
std::string m_robot_tr_poses_topic
bool m_first_time_in_sniff_odom
Initial offset of the received odometry.
int m_pub_seq
Times a messge has been published => usePublishersBroadcasters method is called.
CGraphSlamHandler_ROS(mrpt::system::COutputLogger *logger, TUserOptionsChecker< GRAPH_T > *options_checker, ros::NodeHandle *nh_in)
CGraphSlamHandler_ROS< GRAPH_T > self_t
Handy self type.
std::string m_camera_topic
bool m_received_laser_scan
ros::Publisher m_gridmap_pub
ros::Subscriber m_point_cloud_scan_sub
void sniffOdom(const nav_msgs::Odometry::ConstPtr &ros_odom)
Callback method for handling incoming odometry measurements in a ROS topic.
VerbosityLevel m_min_logging_level
Minimum logging level for the current class instance.
bool continueExec()
Indicate whether graphslam execution can proceed normally.
std::string m_gridmap_topic
void processObservation(mrpt::obs::CObservation::Ptr &observ)
Process an incoming measurement.
size_t m_graph_nodes_last_size
mrpt::obs::CObservationOdometry::Ptr m_mrpt_odom
Received laser scan - converted into MRPT CObservation* format.
ros::Subscriber m_laser_scan_sub
bool m_received_point_cloud
void resetReceivedFlags()
Reset the flags indicating whether we have received new data (odometry, laser scans etc....
ros::Publisher m_robot_trajectory_pub
std::string m_base_link_frame_id
std::string m_point_cloud_topic
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
ros::Subscriber m_odom_sub
ros::Publisher m_odom_trajectory_pub
static const std::string sep_header
mrpt::obs::CObservation2DRangeScan::Ptr m_mrpt_laser_scan
GRAPH_T::constraint_t constraint_t
type of graph constraints
std::string m_stats_topic
std::string m_laser_scan_topic
std::string getParamsAsString()
ros::Subscriber m_camera_scan_sub
static const std::string sep_subheader
ros::Publisher m_gt_trajectory_pub
void readROSParameters()
read configuration parameters from the ROS parameter server.
void setupComm()
Wrapper method around the protected setup* class methods.
void sniffLaserScan(const sensor_msgs::LaserScan::ConstPtr &ros_laser_scan)
Callback method for handling incoming LaserScans objects in a ROS topic.
void getROSParameters(std::string *str_out)
Fill in the given string with the parameters that have been read from the ROS parameter server.
size_t m_measurement_cnt
Total counter of the processed measurements.
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
std::string m_robot_trajectory_topic
std::string m_curr_robot_pos_topic
ros::Publisher m_SLAM_eval_metric_pub
ros::Publisher m_robot_tr_poses_pub
std::string m_odom_frame_id
geometry_msgs::TransformStamped m_anchor_odom_transform
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.