Timing. More...
#include <3d_ndt_mcl.hpp>
Public Member Functions | |
Eigen::Affine3d | getMean () |
Eigen::Vector3d | getMeanVector () |
void | initializeFilter (double x, double y, double z, double roll, double pitch, double yaw, double x_e, double y_e, double z_e, double roll_e, double pitch_e, double yaw_e, unsigned int numParticles) |
NDTMCL3D (double map_resolution, lslgeneric::NDTMap< PointT > &nd_map, double zfilter) | |
void | updateAndPredict (Eigen::Affine3d Tmotion, pcl::PointCloud< PointT > &cloud) |
void | updateAndPredictEff (Eigen::Affine3d Tmotion, pcl::PointCloud< PointT > &cloud) |
Public Attributes | |
int | counter |
bool | forceSIR |
lslgeneric::NDTMap< PointT > | map |
This is my map. | |
ParticleFilter3D | pf |
This is the particle filter. | |
double | resolution |
double | zfilt_min |
Private Attributes | |
bool | isInit |
int | sinceSIR |
Timing.
NDT MCL - Class implementation
Definition at line 21 of file 3d_ndt_mcl.hpp.
NDTMCL3D< PointT >::NDTMCL3D | ( | double | map_resolution, |
lslgeneric::NDTMap< PointT > & | nd_map, | ||
double | zfilter | ||
) | [inline] |
Constructor
First, lets make our target map match the given map This is done because we want (possibly) lower resolution target map
Definition at line 32 of file 3d_ndt_mcl.hpp.
Definition at line 314 of file 3d_ndt_mcl.hpp.
Eigen::Vector3d NDTMCL3D< PointT >::getMeanVector | ( | ) | [inline] |
Definition at line 308 of file 3d_ndt_mcl.hpp.
void NDTMCL3D< PointT >::initializeFilter | ( | double | x, |
double | y, | ||
double | z, | ||
double | roll, | ||
double | pitch, | ||
double | yaw, | ||
double | x_e, | ||
double | y_e, | ||
double | z_e, | ||
double | roll_e, | ||
double | pitch_e, | ||
double | yaw_e, | ||
unsigned int | numParticles | ||
) | [inline] |
Intialize filter to some pose and with some number of particles
Definition at line 80 of file 3d_ndt_mcl.hpp.
void NDTMCL3D< PointT >::updateAndPredict | ( | Eigen::Affine3d | Tmotion, |
pcl::PointCloud< PointT > & | cloud | ||
) | [inline] |
Definition at line 93 of file 3d_ndt_mcl.hpp.
void NDTMCL3D< PointT >::updateAndPredictEff | ( | Eigen::Affine3d | Tmotion, |
pcl::PointCloud< PointT > & | cloud | ||
) | [inline] |
#pragma
Definition at line 193 of file 3d_ndt_mcl.hpp.
Definition at line 26 of file 3d_ndt_mcl.hpp.
Definition at line 28 of file 3d_ndt_mcl.hpp.
Definition at line 323 of file 3d_ndt_mcl.hpp.
lslgeneric::NDTMap<PointT> NDTMCL3D< PointT >::map |
This is my map.
Definition at line 23 of file 3d_ndt_mcl.hpp.
ParticleFilter3D NDTMCL3D< PointT >::pf |
This is the particle filter.
Definition at line 24 of file 3d_ndt_mcl.hpp.
double NDTMCL3D< PointT >::resolution |
Definition at line 25 of file 3d_ndt_mcl.hpp.
Definition at line 324 of file 3d_ndt_mcl.hpp.
Definition at line 27 of file 3d_ndt_mcl.hpp.