The EKFslam class provides EKF SLAM 3d from MRPT libraries. More...
#include <mrpt_ekf_slam_3d.h>

Public Member Functions | |
| EKFslam () | |
| constructor More... | |
| void | init3Dwindow () |
| init 3D window from mrpt lib More... | |
| void | landmark_to_3d (const mrpt::slam::CRangeBearingKFSLAM::KFArray_FEAT &lm, mrpt::math::TPoint3D &p) |
| convert landmark to 3d point More... | |
| void | observation (mrpt::obs::CSensoryFrame::Ptr _sf, mrpt::obs::CObservationOdometry::Ptr _odometry) |
| calculate the actions from odometry model for current observation More... | |
| void | read_iniFile (std::string ini_filename) |
| read ini file More... | |
| void | run3Dwindow () |
| run 3D window update from mrpt lib More... | |
| virtual | ~EKFslam () |
| destructor More... | |
Protected Attributes | |
| mrpt::obs::CActionCollection::Ptr | action |
| actions More... | |
| bool | CAMERA_3DSCENE_FOLLOWS_ROBOT |
| mrpt::math::CMatrixDouble | fullCov_ |
| full covariance matrix More... | |
| mrpt::math::CVectorDouble | fullState_ |
| full state vector More... | |
| std::map< unsigned int, mrpt::maps::CLandmark::TLandmarkID > | LM_IDs_ |
| vector of the landmarks ID More... | |
| std::vector< mrpt::math::TPoint3D > | LMs_ |
| mrpt::slam::CRangeBearingKFSLAM | mapping |
| EKF slam 3d class. More... | |
| std::vector< mrpt::math::TPose3D > | meanPath |
| mrpt::obs::CActionRobotMovement3D::TMotionModelOptions | motion_model_options_ |
| used with odom value motion noise More... | |
| mrpt::poses::CPose3D | odomLastObservation_ |
| last observation of odometry More... | |
| mrpt::poses::CPose3DQuatPDFGaussian | robotPose_ |
| current robot pose More... | |
| mrpt::obs::CSensoryFrame::Ptr | sf |
| observations More... | |
| bool | SHOW_3D_LIVE |
| mrpt::system::TTimeStamp | timeLastUpdate_ |
| last update of the pose and map More... | |
| mrpt::gui::CDisplayWindow3D::Ptr | win3d |
| MRPT window. More... | |
The EKFslam class provides EKF SLAM 3d from MRPT libraries.
Definition at line 35 of file mrpt_ekf_slam_3d.h.
| EKFslam::EKFslam | ( | ) |
constructor
Definition at line 11 of file mrpt_ekf_slam_3d.cpp.
|
virtual |
destructor
Definition at line 37 of file mrpt_ekf_slam_3d.cpp.
| void EKFslam::init3Dwindow | ( | ) |
init 3D window from mrpt lib
Definition at line 95 of file mrpt_ekf_slam_3d.cpp.
| void EKFslam::landmark_to_3d | ( | const mrpt::slam::CRangeBearingKFSLAM::KFArray_FEAT & | lm, |
| mrpt::math::TPoint3D & | p | ||
| ) |
convert landmark to 3d point
Definition at line 210 of file mrpt_ekf_slam_3d.cpp.
| void EKFslam::observation | ( | mrpt::obs::CSensoryFrame::Ptr | _sf, |
| mrpt::obs::CObservationOdometry::Ptr | _odometry | ||
| ) |
calculate the actions from odometry model for current observation
| _sf | current observation |
| _odometry | raw odometry |
Definition at line 70 of file mrpt_ekf_slam_3d.cpp.
| void EKFslam::read_iniFile | ( | std::string | ini_filename | ) |
read ini file
| ini_filename | the name of the ini file to read |
Definition at line 39 of file mrpt_ekf_slam_3d.cpp.
| void EKFslam::run3Dwindow | ( | ) |
run 3D window update from mrpt lib
Definition at line 106 of file mrpt_ekf_slam_3d.cpp.
|
protected |
actions
Definition at line 82 of file mrpt_ekf_slam_3d.h.
|
protected |
Definition at line 92 of file mrpt_ekf_slam_3d.h.
|
protected |
full covariance matrix
Definition at line 98 of file mrpt_ekf_slam_3d.h.
|
protected |
full state vector
Definition at line 99 of file mrpt_ekf_slam_3d.h.
|
protected |
vector of the landmarks ID
Definition at line 97 of file mrpt_ekf_slam_3d.h.
|
protected |
vector of the landmarks
Definition at line 95 of file mrpt_ekf_slam_3d.h.
|
protected |
EKF slam 3d class.
Definition at line 77 of file mrpt_ekf_slam_3d.h.
|
protected |
Definition at line 93 of file mrpt_ekf_slam_3d.h.
|
protected |
used with odom value motion noise
Definition at line 88 of file mrpt_ekf_slam_3d.h.
|
protected |
last observation of odometry
Definition at line 86 of file mrpt_ekf_slam_3d.h.
|
protected |
current robot pose
Definition at line 94 of file mrpt_ekf_slam_3d.h.
|
protected |
observations
Definition at line 83 of file mrpt_ekf_slam_3d.h.
|
protected |
Definition at line 91 of file mrpt_ekf_slam_3d.h.
|
protected |
last update of the pose and map
Definition at line 80 of file mrpt_ekf_slam_3d.h.
|
protected |
MRPT window.
Definition at line 90 of file mrpt_ekf_slam_3d.h.