Public Member Functions | Protected Attributes | List of all members
EKFslam Class Reference

The EKFslam class provides EKF SLAM 3d from MRPT libraries. More...

#include <mrpt_ekf_slam_3d.h>

Inheritance diagram for EKFslam:
Inheritance graph
[legend]

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...
 

Detailed Description

The EKFslam class provides EKF SLAM 3d from MRPT libraries.

Definition at line 35 of file mrpt_ekf_slam_3d.h.

Constructor & Destructor Documentation

◆ EKFslam()

EKFslam::EKFslam ( )

constructor

Definition at line 11 of file mrpt_ekf_slam_3d.cpp.

◆ ~EKFslam()

EKFslam::~EKFslam ( )
virtual

destructor

Definition at line 37 of file mrpt_ekf_slam_3d.cpp.

Member Function Documentation

◆ init3Dwindow()

void EKFslam::init3Dwindow ( )

init 3D window from mrpt lib

Definition at line 95 of file mrpt_ekf_slam_3d.cpp.

◆ landmark_to_3d()

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.

◆ observation()

void EKFslam::observation ( mrpt::obs::CSensoryFrame::Ptr  _sf,
mrpt::obs::CObservationOdometry::Ptr  _odometry 
)

calculate the actions from odometry model for current observation

Parameters
_sfcurrent observation
_odometryraw odometry

Definition at line 70 of file mrpt_ekf_slam_3d.cpp.

◆ read_iniFile()

void EKFslam::read_iniFile ( std::string  ini_filename)

read ini file

Parameters
ini_filenamethe name of the ini file to read

Definition at line 39 of file mrpt_ekf_slam_3d.cpp.

◆ run3Dwindow()

void EKFslam::run3Dwindow ( )

run 3D window update from mrpt lib

Definition at line 106 of file mrpt_ekf_slam_3d.cpp.

Member Data Documentation

◆ action

mrpt::obs::CActionCollection::Ptr EKFslam::action
protected

actions

Definition at line 82 of file mrpt_ekf_slam_3d.h.

◆ CAMERA_3DSCENE_FOLLOWS_ROBOT

bool EKFslam::CAMERA_3DSCENE_FOLLOWS_ROBOT
protected

Definition at line 92 of file mrpt_ekf_slam_3d.h.

◆ fullCov_

mrpt::math::CMatrixDouble EKFslam::fullCov_
protected

full covariance matrix

Definition at line 98 of file mrpt_ekf_slam_3d.h.

◆ fullState_

mrpt::math::CVectorDouble EKFslam::fullState_
protected

full state vector

Definition at line 99 of file mrpt_ekf_slam_3d.h.

◆ LM_IDs_

std::map<unsigned int, mrpt::maps::CLandmark::TLandmarkID> EKFslam::LM_IDs_
protected

vector of the landmarks ID

Definition at line 97 of file mrpt_ekf_slam_3d.h.

◆ LMs_

std::vector<mrpt::math::TPoint3D> EKFslam::LMs_
protected

vector of the landmarks

Definition at line 95 of file mrpt_ekf_slam_3d.h.

◆ mapping

mrpt::slam::CRangeBearingKFSLAM EKFslam::mapping
protected

EKF slam 3d class.

Definition at line 77 of file mrpt_ekf_slam_3d.h.

◆ meanPath

std::vector<mrpt::math::TPose3D> EKFslam::meanPath
protected

Definition at line 93 of file mrpt_ekf_slam_3d.h.

◆ motion_model_options_

mrpt::obs::CActionRobotMovement3D::TMotionModelOptions EKFslam::motion_model_options_
protected

used with odom value motion noise

Definition at line 88 of file mrpt_ekf_slam_3d.h.

◆ odomLastObservation_

mrpt::poses::CPose3D EKFslam::odomLastObservation_
protected

last observation of odometry

Definition at line 86 of file mrpt_ekf_slam_3d.h.

◆ robotPose_

mrpt::poses::CPose3DQuatPDFGaussian EKFslam::robotPose_
protected

current robot pose

Definition at line 94 of file mrpt_ekf_slam_3d.h.

◆ sf

mrpt::obs::CSensoryFrame::Ptr EKFslam::sf
protected

observations

Definition at line 83 of file mrpt_ekf_slam_3d.h.

◆ SHOW_3D_LIVE

bool EKFslam::SHOW_3D_LIVE
protected

Definition at line 91 of file mrpt_ekf_slam_3d.h.

◆ timeLastUpdate_

mrpt::system::TTimeStamp EKFslam::timeLastUpdate_
protected

last update of the pose and map

Definition at line 80 of file mrpt_ekf_slam_3d.h.

◆ win3d

mrpt::gui::CDisplayWindow3D::Ptr EKFslam::win3d
protected

MRPT window.

Definition at line 90 of file mrpt_ekf_slam_3d.h.


The documentation for this class was generated from the following files:


mrpt_ekf_slam_3d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Thu Sep 19 2024 02:26:29