The EKFslam class provides EKF SLAM 2d from MRPT libraries. More...
#include <mrpt_ekf_slam_2d.h>
Public Member Functions | |
EKFslam () | |
constructor More... | |
void | init3Dwindow () |
init 3D window from mrpt lib More... | |
void | landmark_to_3d (const CRangeBearingKFSLAM2D::KFArray_FEAT &lm, TPoint3D &p) |
convert landmark to 3d point More... | |
void | observation (CSensoryFrame::Ptr _sf, 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... | |
The EKFslam class provides EKF SLAM 2d from MRPT libraries.
Definition at line 58 of file mrpt_ekf_slam_2d.h.
EKFslam::EKFslam | ( | ) |
constructor
Definition at line 12 of file mrpt_ekf_slam_2d.cpp.
|
virtual |
destructor
Definition at line 36 of file mrpt_ekf_slam_2d.cpp.
void EKFslam::init3Dwindow | ( | ) |
init 3D window from mrpt lib
Definition at line 92 of file mrpt_ekf_slam_2d.cpp.
convert landmark to 3d point
Definition at line 189 of file mrpt_ekf_slam_2d.cpp.
void EKFslam::observation | ( | CSensoryFrame::Ptr | _sf, |
CObservationOdometry::Ptr | _odometry | ||
) |
calculate the actions from odometry model for current observation
_sf | current observation |
_odometry | raw odometry |
Definition at line 67 of file mrpt_ekf_slam_2d.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 40 of file mrpt_ekf_slam_2d.cpp.
void EKFslam::run3Dwindow | ( | ) |
run 3D window update from mrpt lib
Definition at line 102 of file mrpt_ekf_slam_2d.cpp.
|
protected |
actions
Definition at line 100 of file mrpt_ekf_slam_2d.h.
|
protected |
Definition at line 116 of file mrpt_ekf_slam_2d.h.
|
protected |
full covariance matrix
Definition at line 111 of file mrpt_ekf_slam_2d.h.
|
protected |
full state vector
Definition at line 112 of file mrpt_ekf_slam_2d.h.
|
protected |
vector of the landmarks ID
Definition at line 110 of file mrpt_ekf_slam_2d.h.
|
protected |
vector of the landmarks
Definition at line 109 of file mrpt_ekf_slam_2d.h.
|
protected |
EKF slam 2d class.
Definition at line 96 of file mrpt_ekf_slam_2d.h.
|
protected |
Definition at line 117 of file mrpt_ekf_slam_2d.h.
|
protected |
used if there are is not odom
Definition at line 105 of file mrpt_ekf_slam_2d.h.
|
protected |
used with odom value motion noise
Definition at line 106 of file mrpt_ekf_slam_2d.h.
|
protected |
last observation of odometry
Definition at line 103 of file mrpt_ekf_slam_2d.h.
|
protected |
current robot pose
Definition at line 108 of file mrpt_ekf_slam_2d.h.
|
protected |
observations
Definition at line 101 of file mrpt_ekf_slam_2d.h.
|
protected |
Definition at line 115 of file mrpt_ekf_slam_2d.h.
|
protected |
last update of the pose and map
Definition at line 98 of file mrpt_ekf_slam_2d.h.
|
protected |
used default odom_params
Definition at line 104 of file mrpt_ekf_slam_2d.h.
|
protected |
MRPT window.
Definition at line 114 of file mrpt_ekf_slam_2d.h.