#include <iostream>#include <fstream>#include <string>#include "mrpt_ekf_slam_3d/mrpt_ekf_slam_3d.h"#include <ros/ros.h>#include <ros/package.h>#include "tf2_ros/transform_broadcaster.h"#include "tf2_ros/transform_listener.h"#include "tf2_geometry_msgs/tf2_geometry_msgs.h"#include "geometry_msgs/TransformStamped.h"#include "Eigen/Core"#include "Eigen/Geometry"#include <std_msgs/String.h>#include <std_msgs/Int32.h>#include <geometry_msgs/PoseArray.h>#include <geometry_msgs/PoseWithCovarianceStamped.h>#include <visualization_msgs/MarkerArray.h>#include <visualization_msgs/Marker.h>#include <mrpt/ros1bridge/pose.h>#include <mrpt_msgs_bridge/landmark.h>#include <mrpt/ros1bridge/logging.h>#include <mrpt/ros1bridge/time.h>#include <mrpt/io/CFileGZInputStream.h>#include <mrpt/io/CFileGZOutputStream.h>#include <mrpt/config/CConfigFile.h>#include <mrpt/random.h>#include <mrpt/system/filesystem.h>#include <mrpt/system/os.h>#include <mrpt/poses/CPosePDFGaussian.h>#include <mrpt/poses/CPose3DPDF.h>#include <mrpt/opengl/CSetOfLines.h>#include <mrpt/opengl/CGridPlaneXY.h>#include <mrpt/opengl/CEllipsoid3D.h>#include <mrpt/opengl/stock_objects.h>#include <mrpt_msgs/ObservationRangeBearing.h>#include <mrpt/obs/CActionRobotMovement2D.h>#include <mrpt/obs/CActionRobotMovement3D.h>#include <mrpt/obs/CObservationOdometry.h>#include <mrpt/obs/CRawlog.h>

Go to the source code of this file.
Classes | |
| class | EKFslamWrapper |
| The EKFslamWrapper class provides the ROS wrapper for EKF SLAM 3d from MRPT libraries. More... | |