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

Protected Attributes

CActionCollection::Ptr action
 actions More...
 
bool CAMERA_3DSCENE_FOLLOWS_ROBOT
 
CMatrixDouble fullCov_
 full covariance matrix More...
 
CVectorDouble fullState_
 full state vector More...
 
std::map< unsigned int, CLandmark::TLandmarkIDLM_IDs_
 vector of the landmarks ID More...
 
std::vector< mrpt::math::TPoint3DLMs_
 vector of the landmarks More...
 
CRangeBearingKFSLAM mapping
 EKF slam 3d class. More...
 
vector< TPose3DmeanPath
 
mrpt::poses::CPose3D odomLastObservation_
 last observation of odometry More...
 
CPose3DQuatPDFGaussian robotPose_
 current robot pose More...
 
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 57 of file mrpt_ekf_slam_3d.h.

Constructor & Destructor Documentation

EKFslam::EKFslam ( )

constructor

Definition at line 13 of file mrpt_ekf_slam_3d.cpp.

EKFslam::~EKFslam ( )
virtual

destructor

Definition at line 38 of file mrpt_ekf_slam_3d.cpp.

Member Function Documentation

void EKFslam::init3Dwindow ( )

init 3D window from mrpt lib

Definition at line 96 of file mrpt_ekf_slam_3d.cpp.

void EKFslam::landmark_to_3d ( const CRangeBearingKFSLAM::KFArray_FEAT &  lm,
TPoint3D p 
)

convert landmark to 3d point

Definition at line 193 of file mrpt_ekf_slam_3d.cpp.

void EKFslam::observation ( CSensoryFrame::Ptr  _sf,
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.

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

read ini file

Parameters
ini_filenamethe name of the ini file to read

Definition at line 42 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.

Member Data Documentation

CActionCollection::Ptr EKFslam::action
protected

actions

Definition at line 99 of file mrpt_ekf_slam_3d.h.

bool EKFslam::CAMERA_3DSCENE_FOLLOWS_ROBOT
protected

Definition at line 109 of file mrpt_ekf_slam_3d.h.

CMatrixDouble EKFslam::fullCov_
protected

full covariance matrix

Definition at line 114 of file mrpt_ekf_slam_3d.h.

CVectorDouble EKFslam::fullState_
protected

full state vector

Definition at line 115 of file mrpt_ekf_slam_3d.h.

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

vector of the landmarks ID

Definition at line 113 of file mrpt_ekf_slam_3d.h.

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

vector of the landmarks

Definition at line 112 of file mrpt_ekf_slam_3d.h.

CRangeBearingKFSLAM EKFslam::mapping
protected

EKF slam 3d class.

Definition at line 95 of file mrpt_ekf_slam_3d.h.

vector<TPose3D> EKFslam::meanPath
protected

Definition at line 110 of file mrpt_ekf_slam_3d.h.

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

last observation of odometry

Definition at line 102 of file mrpt_ekf_slam_3d.h.

CPose3DQuatPDFGaussian EKFslam::robotPose_
protected

current robot pose

Definition at line 111 of file mrpt_ekf_slam_3d.h.

CSensoryFrame::Ptr EKFslam::sf
protected

observations

Definition at line 100 of file mrpt_ekf_slam_3d.h.

bool EKFslam::SHOW_3D_LIVE
protected

Definition at line 108 of file mrpt_ekf_slam_3d.h.

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

last update of the pose and map

Definition at line 97 of file mrpt_ekf_slam_3d.h.

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

MRPT window.

Definition at line 107 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 Sat May 2 2020 03:44:08