Go to the documentation of this file.
9 #include <mrpt/config/CConfigFile.h>
10 #include <mrpt/io/CFileGZInputStream.h>
11 #include <mrpt/io/CFileGZOutputStream.h>
12 #include <mrpt/system/os.h>
13 #include <mrpt/system/string_utils.h>
14 #include <mrpt/system/filesystem.h>
15 #include <mrpt/slam/CRangeBearingKFSLAM.h>
16 #include <mrpt/math/ops_containers.h>
17 #include <mrpt/opengl/CGridPlaneXY.h>
18 #include <mrpt/opengl/CSetOfLines.h>
19 #include <mrpt/opengl/COpenGLScene.h>
20 #include <mrpt/opengl/stock_objects.h>
21 #include <mrpt/gui/CDisplayWindow3D.h>
22 #include <mrpt/obs/CActionRobotMovement2D.h>
23 #include <mrpt/obs/CActionRobotMovement3D.h>
24 #include <mrpt/obs/CActionCollection.h>
25 #include <mrpt/obs/CObservationOdometry.h>
26 #include <mrpt/obs/CSensoryFrame.h>
27 #include <mrpt/maps/CMultiMetricMap.h>
28 #include <mrpt/obs/CObservationBearingRange.h>
29 #include <mrpt/obs/CRawlog.h>
58 const mrpt::slam::CRangeBearingKFSLAM::KFArray_FEAT& lm,
59 mrpt::math::TPoint3D& p);
73 mrpt::obs::CSensoryFrame::Ptr _sf,
74 mrpt::obs::CObservationOdometry::Ptr _odometry);
79 mrpt::system::TTimeStamp
82 mrpt::obs::CActionCollection::Ptr
action;
83 mrpt::obs::CSensoryFrame::Ptr
sf;
87 mrpt::obs::CActionRobotMovement3D::TMotionModelOptions
90 mrpt::gui::CDisplayWindow3D::Ptr
win3d;
95 std::vector<mrpt::math::TPoint3D>
LMs_;
96 std::map<unsigned int, mrpt::maps::CLandmark::TLandmarkID>
LM_IDs_;
bool CAMERA_3DSCENE_FOLLOWS_ROBOT
virtual ~EKFslam()
destructor
void observation(mrpt::obs::CSensoryFrame::Ptr _sf, mrpt::obs::CObservationOdometry::Ptr _odometry)
calculate the actions from odometry model for current observation
mrpt::gui::CDisplayWindow3D::Ptr win3d
MRPT window.
void landmark_to_3d(const mrpt::slam::CRangeBearingKFSLAM::KFArray_FEAT &lm, mrpt::math::TPoint3D &p)
convert landmark to 3d point
The EKFslam class provides EKF SLAM 3d from MRPT libraries.
mrpt::slam::CRangeBearingKFSLAM mapping
EKF slam 3d class.
void init3Dwindow()
init 3D window from mrpt lib
mrpt::system::TTimeStamp timeLastUpdate_
last update of the pose and map
std::map< unsigned int, mrpt::maps::CLandmark::TLandmarkID > LM_IDs_
vector of the landmarks ID
std::vector< mrpt::math::TPoint3D > LMs_
mrpt::poses::CPose3DQuatPDFGaussian robotPose_
current robot pose
void run3Dwindow()
run 3D window update from mrpt lib
mrpt::math::CMatrixDouble fullCov_
full covariance matrix
mrpt::poses::CPose3D odomLastObservation_
last observation of odometry
void read_iniFile(std::string ini_filename)
read ini file
mrpt::obs::CActionCollection::Ptr action
actions
std::vector< mrpt::math::TPose3D > meanPath
mrpt::obs::CSensoryFrame::Ptr sf
observations
mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motion_model_options_
used with odom value motion noise
mrpt::math::CVectorDouble fullState_
full state vector
mrpt_ekf_slam_3d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Thu Sep 19 2024 02:26:29