Public Member Functions | Public Attributes | Private Attributes
NDTMCL3D< PointT > Class Template Reference

Timing. More...

#include <3d_ndt_mcl.hpp>

List of all members.

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< PointTmap
 This is my map.
ParticleFilter3D pf
 This is the particle filter.
double resolution
double resolution_sensor
double zfilt_min

Private Attributes

bool isInit
int sinceSIR

Detailed Description

template<typename PointT>
class NDTMCL3D< PointT >

Timing.

NDT MCL - Class implementation

Definition at line 21 of file 3d_ndt_mcl.hpp.


Constructor & Destructor Documentation

template<typename PointT >
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 33 of file 3d_ndt_mcl.hpp.


Member Function Documentation

template<typename PointT >
Eigen::Affine3d NDTMCL3D< PointT >::getMean ( ) [inline]

Definition at line 316 of file 3d_ndt_mcl.hpp.

template<typename PointT >
Eigen::Vector3d NDTMCL3D< PointT >::getMeanVector ( ) [inline]

Definition at line 310 of file 3d_ndt_mcl.hpp.

template<typename PointT >
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 82 of file 3d_ndt_mcl.hpp.

template<typename PointT >
void NDTMCL3D< PointT >::updateAndPredict ( Eigen::Affine3d  Tmotion,
pcl::PointCloud< PointT > &  cloud 
) [inline]

Definition at line 95 of file 3d_ndt_mcl.hpp.

template<typename PointT >
void NDTMCL3D< PointT >::updateAndPredictEff ( Eigen::Affine3d  Tmotion,
pcl::PointCloud< PointT > &  cloud 
) [inline]

#pragma

Definition at line 195 of file 3d_ndt_mcl.hpp.


Member Data Documentation

template<typename PointT >
int NDTMCL3D< PointT >::counter

Definition at line 27 of file 3d_ndt_mcl.hpp.

template<typename PointT >
bool NDTMCL3D< PointT >::forceSIR

Definition at line 29 of file 3d_ndt_mcl.hpp.

template<typename PointT >
bool NDTMCL3D< PointT >::isInit [private]

Definition at line 325 of file 3d_ndt_mcl.hpp.

template<typename PointT >
lslgeneric::NDTMap<PointT> NDTMCL3D< PointT >::map

This is my map.

Definition at line 23 of file 3d_ndt_mcl.hpp.

template<typename PointT >
ParticleFilter3D NDTMCL3D< PointT >::pf

This is the particle filter.

Definition at line 24 of file 3d_ndt_mcl.hpp.

template<typename PointT >
double NDTMCL3D< PointT >::resolution

Definition at line 25 of file 3d_ndt_mcl.hpp.

template<typename PointT >
double NDTMCL3D< PointT >::resolution_sensor

Definition at line 26 of file 3d_ndt_mcl.hpp.

template<typename PointT >
int NDTMCL3D< PointT >::sinceSIR [private]

Definition at line 326 of file 3d_ndt_mcl.hpp.

template<typename PointT >
double NDTMCL3D< PointT >::zfilt_min

Definition at line 28 of file 3d_ndt_mcl.hpp.


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


ndt_mcl
Author(s): Jari Saarinen
autogenerated on Mon Oct 6 2014 03:20:03