Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
NDTMCL Class Reference

#include <ndt_mcl.h>

List of all members.

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

Detailed Description

NDT MCL - Class implementation

Definition at line 22 of file ndt_mcl.h.


Constructor & Destructor Documentation

NDTMCL::NDTMCL ( double  map_resolution,
lslgeneric::NDTMap 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.h.


Member Function Documentation

Eigen::Affine3d NDTMCL::getAsAffine ( int  i) [inline, private]

Definition at line 97 of file ndt_mcl.h.

Eigen::Vector3d NDTMCL::getMean ( ) [inline]

Definition at line 87 of file ndt_mcl.h.

void NDTMCL::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.h.

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.


Member Data Documentation

Definition at line 27 of file ndt_mcl.h.

Definition at line 29 of file ndt_mcl.h.

bool NDTMCL::isInit [private]

Definition at line 95 of file ndt_mcl.h.

This is my map.

Definition at line 24 of file ndt_mcl.h.

This is the particle filter.

Definition at line 25 of file ndt_mcl.h.

Definition at line 26 of file ndt_mcl.h.

int NDTMCL::sinceSIR [private]

Definition at line 96 of file ndt_mcl.h.

Definition at line 28 of file ndt_mcl.h.


The documentation for this class was generated from the following files:


ndt_mcl
Author(s): Jari Saarinen
autogenerated on Wed Aug 26 2015 15:25:02