#include <ndt_mcl.hpp>
Public Member Functions | |
Eigen::Vector3d | getMean () |
void | initializeFilter (double x, double y, double yaw, double x_e, double y_e, double yaw_e, int numParticles) |
NDTMCL (double map_resolution, lslgeneric::NDTMap< PointT > &nd_map, double zfilter) | |
void | updateAndPredict (Eigen::Affine3d Tmotion, pcl::PointCloud< PointT > &cloud) |
Public Attributes | |
int | counter |
bool | forceSIR |
lslgeneric::NDTMap< PointT > | map |
This is my map. | |
mcl::CParticleFilter | pf |
This is the particle filter. | |
double | resolution |
double | zfilt_min |
Private Member Functions | |
Eigen::Affine3d | getAsAffine (int i) |
Private Attributes | |
bool | isInit |
int | sinceSIR |
NDT MCL - Class implementation
Definition at line 22 of file ndt_mcl.hpp.
NDTMCL< PointT >::NDTMCL | ( | 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 33 of file ndt_mcl.hpp.
Eigen::Affine3d NDTMCL< PointT >::getAsAffine | ( | int | i | ) | [inline, private] |
Definition at line 203 of file ndt_mcl.hpp.
Definition at line 193 of file ndt_mcl.hpp.
void NDTMCL< PointT >::initializeFilter | ( | double | x, |
double | y, | ||
double | yaw, | ||
double | x_e, | ||
double | y_e, | ||
double | yaw_e, | ||
int | numParticles | ||
) | [inline] |
Intialize filter to some pose and with some number of particles
Definition at line 81 of file ndt_mcl.hpp.
void NDTMCL< PointT >::updateAndPredict | ( | Eigen::Affine3d | Tmotion, |
pcl::PointCloud< PointT > & | cloud | ||
) | [inline] |
Arla Motion model if(rot[2]<(0.5 * M_PI/180.0) && tr[0]>=0){ pf.predict(mcl::pose(tr[0],tr[1],rot[2]), mcl::pose(tr[0]*0.2 + 0.005,tr[1]*0.1+ 0.005,rot[2]*0.2+0.001)); }else if(tr[0]>=0){ pf.predict(mcl::pose(tr[0],tr[1],rot[2]), mcl::pose(tr[0] + 0.01,tr[1] + 0.01,rot[2]*0.5+0.001)); }else{ pf.predict(mcl::pose(tr[0],tr[1],rot[2]), mcl::pose(tr[0] + 0.02,tr[1] + 0.01,rot[2]*0.8+0.001)); }
Definition at line 85 of file ndt_mcl.hpp.
Definition at line 27 of file ndt_mcl.hpp.
Definition at line 29 of file ndt_mcl.hpp.
Definition at line 201 of file ndt_mcl.hpp.
lslgeneric::NDTMap<PointT> NDTMCL< PointT >::map |
This is my map.
Definition at line 24 of file ndt_mcl.hpp.
mcl::CParticleFilter NDTMCL< PointT >::pf |
This is the particle filter.
Definition at line 25 of file ndt_mcl.hpp.
double NDTMCL< PointT >::resolution |
Definition at line 26 of file ndt_mcl.hpp.
Definition at line 202 of file ndt_mcl.hpp.
Definition at line 28 of file ndt_mcl.hpp.