mrpt_ekf_slam_3d_wrapper.h
Go to the documentation of this file.
00001 /*
00002  * File: mrpt_ekf_slam_3d_wrapper.h
00003  * Author: Vladislav Tananaev
00004  *
00005  */
00006 
00007 #ifndef MRPT_EKF_SLAM_3D_WRAPPER_H
00008 #define MRPT_EKF_SLAM_3D_WRAPPER_H
00009 #include <iostream>  // std::cout
00010 #include <fstream>   // std::ifstream
00011 #include <string>
00012 #include "mrpt_ekf_slam_3d/mrpt_ekf_slam_3d.h"
00013 // add ros libraries
00014 #include <ros/ros.h>
00015 #include <ros/package.h>
00016 #include <tf/transform_listener.h>
00017 #include <tf/transform_broadcaster.h>
00018 //#include <tf_conversions/tf_eigen.h>
00019 #include "Eigen/Core"
00020 #include "Eigen/Geometry"
00021 // add ros msgs
00022 #include <std_msgs/String.h>
00023 #include <std_msgs/Int32.h>
00024 #include <geometry_msgs/PoseArray.h>
00025 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00026 #include <visualization_msgs/MarkerArray.h>
00027 #include <visualization_msgs/Marker.h>
00028 // mrpt bridge libs
00029 #include <mrpt_bridge/pose.h>
00030 #include <mrpt_bridge/landmark.h>
00031 #include <mrpt_bridge/mrpt_log_macros.h>
00032 #include <mrpt_bridge/time.h>
00033 #include <mrpt/utils/CFileGZInputStream.h>
00034 #include <mrpt/utils/CFileGZOutputStream.h>
00035 #include <mrpt/utils/CConfigFile.h>
00036 #include <mrpt/random.h>
00037 #include <mrpt/system/threads.h>
00038 #include <mrpt/system/filesystem.h>
00039 #include <mrpt/system/os.h>
00040 #include <mrpt/poses/CPosePDFGaussian.h>
00041 #include <mrpt/poses/CPose3DPDF.h>
00042 #include <mrpt/opengl/CSetOfLines.h>
00043 #include <mrpt/opengl/CGridPlaneXY.h>
00044 #include <mrpt/opengl/CEllipsoid.h>
00045 #include <mrpt/opengl/stock_objects.h>
00046 #include <mrpt_msgs/ObservationRangeBearing.h>
00047 
00048 #if MRPT_VERSION >= 0x130
00049 #include <mrpt/obs/CActionRobotMovement2D.h>
00050 #include <mrpt/obs/CActionRobotMovement3D.h>
00051 #include <mrpt/obs/CObservationOdometry.h>
00052 #include <mrpt/obs/CRawlog.h>
00053 using namespace mrpt::maps;
00054 using namespace mrpt::obs;
00055 #else
00056 #include <mrpt/slam/CActionRobotMovement2D.h>
00057 #include <mrpt/slam/CActionRobotMovement3D.h>
00058 #include <mrpt/slam/CObservationOdometry.h>
00059 #include <mrpt/slam/CRawlog.h>
00060 #endif
00061 
00066 class EKFslamWrapper : EKFslam
00067 {
00068 public:
00072   EKFslamWrapper();
00076   ~EKFslamWrapper();
00080   void get_param();
00088   void makeRightHanded(Eigen::Matrix3d& eigenvectors, Eigen::Vector3d& eigenvalues);
00089 
00097   void computeEllipseOrientationScale(tf::Quaternion& orientation, Eigen::Vector3d& scale,
00098                                       const mrpt::math::CMatrixDouble covariance);
00102   void init();
00108   bool rawlogPlay();
00114   bool is_file_exists(const std::string& name);
00118   void viz_state();
00122   void viz_dataAssociation();
00129   void odometryForCallback(CObservationOdometryPtr& _odometry, const std_msgs::Header& _msg_header);
00140   void landmarkCallback(const mrpt_msgs::ObservationRangeBearing& _msg);
00146   void updateSensorPose(std::string _frame_id);
00159   bool waitForTransform(mrpt::poses::CPose3D& des, const std::string& target_frame, const std::string& source_frame,
00160                         const ros::Time& time, const ros::Duration& timeout,
00161                         const ros::Duration& polling_sleep_duration = ros::Duration(0.01));
00166   void publishTF();
00167 
00168 private:
00169   ros::NodeHandle n_;        
00170   double rawlog_play_delay;  
00171   double ellipse_scale_;
00172   bool rawlog_play_;  
00173   // Subscribers
00174   std::vector<ros::Subscriber> sensorSub_;  
00175   std::string rawlog_filename;              
00176   std::string ini_filename;                 
00177   std::string global_frame_id;              
00178   std::string odom_frame_id;                
00179   std::string base_frame_id;                
00180 
00181   // Sensor source
00182   std::string sensor_source;  
00183 
00184   std::map<std::string, mrpt::poses::CPose3D> landmark_poses_;  
00185 
00186   CTicTac tictac;  
00187   float t_exec;    
00188 
00189   ros::Publisher data_association_viz_pub_, state_viz_pub_;
00190   tf::TransformListener listenerTF_;         
00191   tf::TransformBroadcaster tf_broadcaster_;  
00192 };
00193 
00194 #endif /* MRPT_EKF_SLAM_3D_WRAPPER_H */


mrpt_ekf_slam_3d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Sun Sep 17 2017 03:02:02