#include <ros/ros.h>#include <mrpt_bridge/mrpt_bridge.h>#include <mrpt_msgs/GraphSlamStats.h>#include <geometry_msgs/PoseStamped.h>#include <geometry_msgs/PoseArray.h>#include <geometry_msgs/TransformStamped.h>#include <sensor_msgs/LaserScan.h>#include <nav_msgs/Path.h>#include <nav_msgs/Odometry.h>#include <nav_msgs/OccupancyGrid.h>#include <std_msgs/Header.h>#include <tf/transform_datatypes.h>#include <tf2_ros/buffer.h>#include <tf2_ros/transform_broadcaster.h>#include <tf2_ros/transform_listener.h>#include <tf2/LinearMath/Quaternion.h>#include <tf2/LinearMath/Vector3.h>#include <mrpt/graphs/CNetworkOfPoses.h>#include <mrpt/maps/COccupancyGridMap2D.h>#include <mrpt/obs/CObservationOdometry.h>#include <mrpt/obs/CObservation2DRangeScan.h>#include <mrpt/system/string_utils.h>#include <mrpt/system/filesystem.h>#include <mrpt/system/os.h>#include <mrpt/utils/COutputLogger.h>#include <mrpt/graphslam/apps_related/CGraphSlamHandler.h>#include "mrpt_graphslam_2d/CGraphSlamEngine_ROS.h"#include "mrpt_graphslam_2d/CGraphSlamEngine_MR.h"#include "mrpt_graphslam_2d/TUserOptionsChecker_ROS.h"#include <string>#include <sstream>#include <vector>#include "mrpt_graphslam_2d/CGraphSlamHandler_ROS_impl.h"

Go to the source code of this file.
Classes | |
| class | mrpt::graphslam::apps::CGraphSlamHandler_ROS< GRAPH_T > |
| Manage variables, ROS parameters and everything else related to the graphslam-engine ROS wrapper. More... | |
Namespaces | |
| namespace | mrpt |
| namespace | mrpt::graphslam |
| namespace | mrpt::graphslam::apps |