#include <ndt_mcl.h>
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 &nd_map, double zfilter) | |
| void | updateAndPredict (Eigen::Affine3d Tmotion, pcl::PointCloud< pcl::PointXYZ > &cloud) |
Public Attributes | |
| int | counter |
| bool | forceSIR |
| lslgeneric::NDTMap | 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 |
| NDTMCL::NDTMCL | ( | double | map_resolution, |
| lslgeneric::NDTMap & | nd_map, | ||
| double | zfilter | ||
| ) | [inline] |
| Eigen::Affine3d NDTMCL::getAsAffine | ( | int | i | ) | [inline, private] |
| Eigen::Vector3d NDTMCL::getMean | ( | ) | [inline] |
| void NDTMCL::initializeFilter | ( | double | x, |
| double | y, | ||
| double | yaw, | ||
| double | x_e, | ||
| double | y_e, | ||
| double | yaw_e, | ||
| int | numParticles | ||
| ) | [inline] |
| void NDTMCL::updateAndPredict | ( | Eigen::Affine3d | Tmotion, |
| pcl::PointCloud< pcl::PointXYZ > & | cloud | ||
| ) |
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 3 of file ndt_mcl.cpp.
| int NDTMCL::counter |
| bool NDTMCL::forceSIR |
bool NDTMCL::isInit [private] |
| double NDTMCL::resolution |
int NDTMCL::sinceSIR [private] |
| double NDTMCL::zfilt_min |