The PFslam class provides Rao-Blackwellized Particle filter SLAM from MRPT libraries. More...
#include <mrpt_rbpf_slam.h>
Classes | |
struct | Options |
Public Member Functions | |
void | init3Dwindow () |
void | initSlam (Options options) |
initialize the SLAM More... | |
void | observation (const mrpt::obs::CSensoryFrame::ConstPtr sensory_frame, const mrpt::obs::CObservationOdometry::ConstPtr odometry) |
Calculate the actions from odometry model for current observation. More... | |
PFslam ()=default | |
void | readIniFile (const std::string &ini_filename) |
Read ini file. More... | |
void | readRawlog (const std::string &rawlog_filename, std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame >> &data) |
Read pairs of actions and observations from rawlog file. More... | |
void | run3Dwindow () |
virtual | ~PFslam () |
Public Attributes | |
struct mrpt_rbpf_slam::PFslam::Options | options_ |
Protected Attributes | |
mrpt::obs::CActionCollection::Ptr | action_ |
actions More... | |
mrpt::poses::CPose3DPDFParticles | curPDF |
current robot pose More... | |
mrpt::slam::CMetricMapBuilderRBPF | mapBuilder_ |
map builder More... | |
const mrpt::maps::CMultiMetricMap * | metric_map_ |
receive map after iteration of SLAM to metric map More... | |
mrpt::poses::CPose2D | odomLastObservation_ |
last observation of odometry More... | |
mrpt::obs::CSensoryFrame::Ptr | sensory_frame_ |
observations More... | |
mrpt::system::TTimeStamp | timeLastUpdate_ |
last update of the pose and map More... | |
bool | use_motion_model_default_options_ |
used default odom_params More... | |
mrpt::gui::CDisplayWindow3D::Ptr | win3D_ |
MRPT window. More... | |
The PFslam class provides Rao-Blackwellized Particle filter SLAM from MRPT libraries.
Definition at line 47 of file mrpt_rbpf_slam.h.
|
default |
|
virtual |
Definition at line 16 of file mrpt_rbpf_slam.cpp.
void mrpt_rbpf_slam::PFslam::init3Dwindow | ( | ) |
Definition at line 150 of file mrpt_rbpf_slam.cpp.
void mrpt_rbpf_slam::PFslam::initSlam | ( | PFslam::Options | options | ) |
initialize the SLAM
Definition at line 104 of file mrpt_rbpf_slam.cpp.
void mrpt_rbpf_slam::PFslam::observation | ( | const mrpt::obs::CSensoryFrame::ConstPtr | sensory_frame, |
const mrpt::obs::CObservationOdometry::ConstPtr | odometry | ||
) |
Calculate the actions from odometry model for current observation.
[in] | sensory_frame | current observation |
[in] | odometry | raw odometry |
Definition at line 85 of file mrpt_rbpf_slam.cpp.
void mrpt_rbpf_slam::PFslam::readIniFile | ( | const std::string & | ini_filename | ) |
Read ini file.
[in] | ini_filename | the name of the ini file to read |
Definition at line 43 of file mrpt_rbpf_slam.cpp.
void mrpt_rbpf_slam::PFslam::readRawlog | ( | const std::string & | rawlog_filename, |
std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame >> & | data | ||
) |
Read pairs of actions and observations from rawlog file.
[in] | rawlog_filename | the name of rawlog file to read |
[out] | data | vector of pairs of actions and observations |
Definition at line 54 of file mrpt_rbpf_slam.cpp.
void mrpt_rbpf_slam::PFslam::run3Dwindow | ( | ) |
Definition at line 162 of file mrpt_rbpf_slam.cpp.
|
protected |
actions
Definition at line 101 of file mrpt_rbpf_slam.h.
|
protected |
current robot pose
Definition at line 109 of file mrpt_rbpf_slam.h.
|
protected |
map builder
Definition at line 100 of file mrpt_rbpf_slam.h.
|
protected |
receive map after iteration of SLAM to metric map
Definition at line 108 of file mrpt_rbpf_slam.h.
|
protected |
last observation of odometry
Definition at line 104 of file mrpt_rbpf_slam.h.
struct mrpt_rbpf_slam::PFslam::Options mrpt_rbpf_slam::PFslam::options_ |
|
protected |
observations
Definition at line 102 of file mrpt_rbpf_slam.h.
|
protected |
last update of the pose and map
Definition at line 106 of file mrpt_rbpf_slam.h.
|
protected |
used default odom_params
Definition at line 105 of file mrpt_rbpf_slam.h.
|
protected |
MRPT window.
Definition at line 111 of file mrpt_rbpf_slam.h.