The PFslam class provides Rao-Blackwellized Particle filter SLAM from MRPT libraries. More...
#include <mrpt_rbpf_slam.h>
Public Member Functions | |
void | init3Dwindow () |
void | init_slam () |
initialize the SLAM | |
void | observation (CSensoryFramePtr _sf, CObservationOdometryPtr _odometry) |
calculate the actions from odometry model for current observation | |
PFslam () | |
constructor | |
void | read_iniFile (std::string ini_filename) |
read ini file | |
void | read_rawlog (std::vector< std::pair< CActionCollection, CSensoryFrame >> &data, std::string rawlog_filename) |
read pairs of actions and observations from rawlog file | |
void | run3Dwindow () |
virtual | ~PFslam () |
destructor | |
Protected Attributes | |
CActionCollectionPtr | action |
actions | |
bool | CAMERA_3DSCENE_FOLLOWS_ROBOT |
CPose3DPDFParticles | curPDF |
current robot pose | |
CMetricMapBuilderRBPF * | mapBuilder |
map builder | |
const CMultiMetricMap * | metric_map_ |
receive map after iteration of SLAM to metric map | |
CActionRobotMovement2D::TMotionModelOptions | motion_model_default_options_ |
used if there are is not odom | |
CActionRobotMovement2D::TMotionModelOptions | motion_model_options_ |
used with odom value motion noise | |
mrpt::poses::CPose2D | odomLastObservation_ |
last observation of odometry | |
int | PROGRESS_WINDOW_HEIGHT |
int | PROGRESS_WINDOW_WIDTH |
CMetricMapBuilderRBPF::TConstructionOptions | rbpfMappingOptions |
options for SLAM from ini file | |
CSensoryFramePtr | sf |
observations | |
bool | SHOW_PROGRESS_IN_WINDOW |
int | SHOW_PROGRESS_IN_WINDOW_DELAY_MS |
mrpt::system::TTimeStamp | timeLastUpdate_ |
last update of the pose and map | |
bool | use_motion_model_default_options_ |
used default odom_params | |
mrpt::gui::CDisplayWindow3DPtr | win3D |
MRPT window. |
The PFslam class provides Rao-Blackwellized Particle filter SLAM from MRPT libraries.
Definition at line 70 of file mrpt_rbpf_slam.h.
PFslam::PFslam | ( | ) |
constructor
Definition at line 13 of file mrpt_rbpf_slam.cpp.
PFslam::~PFslam | ( | ) | [virtual] |
destructor
Definition at line 39 of file mrpt_rbpf_slam.cpp.
void PFslam::init3Dwindow | ( | ) |
Definition at line 145 of file mrpt_rbpf_slam.cpp.
void PFslam::init_slam | ( | ) |
initialize the SLAM
Definition at line 128 of file mrpt_rbpf_slam.cpp.
void PFslam::observation | ( | CSensoryFramePtr | _sf, |
CObservationOdometryPtr | _odometry | ||
) |
calculate the actions from odometry model for current observation
_sf | current observation |
_odometry | raw odometry |
Definition at line 103 of file mrpt_rbpf_slam.cpp.
void PFslam::read_iniFile | ( | std::string | ini_filename | ) |
read ini file
ini_filename | the name of the ini file to read |
Definition at line 62 of file mrpt_rbpf_slam.cpp.
void PFslam::read_rawlog | ( | std::vector< std::pair< CActionCollection, CSensoryFrame >> & | data, |
std::string | rawlog_filename | ||
) |
read pairs of actions and observations from rawlog file
data | vector of pairs of actions and observations |
rawlog_filename | the name of rawlog file to read |
Definition at line 77 of file mrpt_rbpf_slam.cpp.
void PFslam::run3Dwindow | ( | ) |
Definition at line 160 of file mrpt_rbpf_slam.cpp.
CActionCollectionPtr PFslam::action [protected] |
actions
Definition at line 116 of file mrpt_rbpf_slam.h.
bool PFslam::CAMERA_3DSCENE_FOLLOWS_ROBOT [protected] |
Definition at line 131 of file mrpt_rbpf_slam.h.
CPose3DPDFParticles PFslam::curPDF [protected] |
current robot pose
Definition at line 128 of file mrpt_rbpf_slam.h.
CMetricMapBuilderRBPF* PFslam::mapBuilder [protected] |
map builder
Definition at line 115 of file mrpt_rbpf_slam.h.
const CMultiMetricMap* PFslam::metric_map_ [protected] |
receive map after iteration of SLAM to metric map
Definition at line 127 of file mrpt_rbpf_slam.h.
CActionRobotMovement2D::TMotionModelOptions PFslam::motion_model_default_options_ [protected] |
used if there are is not odom
Definition at line 121 of file mrpt_rbpf_slam.h.
CActionRobotMovement2D::TMotionModelOptions PFslam::motion_model_options_ [protected] |
used with odom value motion noise
Definition at line 122 of file mrpt_rbpf_slam.h.
mrpt::poses::CPose2D PFslam::odomLastObservation_ [protected] |
last observation of odometry
Definition at line 119 of file mrpt_rbpf_slam.h.
int PFslam::PROGRESS_WINDOW_HEIGHT [protected] |
Definition at line 134 of file mrpt_rbpf_slam.h.
int PFslam::PROGRESS_WINDOW_WIDTH [protected] |
Definition at line 134 of file mrpt_rbpf_slam.h.
CMetricMapBuilderRBPF::TConstructionOptions PFslam::rbpfMappingOptions [protected] |
options for SLAM from ini file
Definition at line 124 of file mrpt_rbpf_slam.h.
CSensoryFramePtr PFslam::sf [protected] |
observations
Definition at line 117 of file mrpt_rbpf_slam.h.
bool PFslam::SHOW_PROGRESS_IN_WINDOW [protected] |
Definition at line 132 of file mrpt_rbpf_slam.h.
int PFslam::SHOW_PROGRESS_IN_WINDOW_DELAY_MS [protected] |
Definition at line 133 of file mrpt_rbpf_slam.h.
mrpt::system::TTimeStamp PFslam::timeLastUpdate_ [protected] |
last update of the pose and map
Definition at line 125 of file mrpt_rbpf_slam.h.
bool PFslam::use_motion_model_default_options_ [protected] |
used default odom_params
Definition at line 120 of file mrpt_rbpf_slam.h.
mrpt::gui::CDisplayWindow3DPtr PFslam::win3D [protected] |
MRPT window.
Definition at line 130 of file mrpt_rbpf_slam.h.