Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
humanoid_localization::RaycastingModel Class Reference

#include <RaycastingModel.h>

Inheritance diagram for humanoid_localization::RaycastingModel:
Inheritance graph
[legend]

Public Member Functions

virtual void integrateMeasurement (Particles &particles, const PointCloud &pc, const std::vector< float > &ranges, float max_range, const tf::Transform &baseToSensor)
 
 RaycastingModel (ros::NodeHandle *nh, boost::shared_ptr< MapModel > mapModel, EngineT *rngEngine)
 
virtual ~RaycastingModel ()
 
- Public Member Functions inherited from humanoid_localization::ObservationModel
virtual void integratePoseMeasurement (Particles &particles, double roll, double pitch, const tf::StampedTransform &footprintToTorso)
 
 ObservationModel (ros::NodeHandle *nh, boost::shared_ptr< MapModel > mapModel, EngineT *rngEngine)
 
virtual void setMap (boost::shared_ptr< octomap::OcTree > map)
 
virtual ~ObservationModel ()
 

Protected Member Functions

bool getHeightError (const Particle &p, const tf::StampedTransform &footprintToBase, double &heightError) const
 

Protected Attributes

bool m_filterPointCloudGround
 
double m_groundFilterAngle
 
double m_groundFilterDistance
 
double m_groundFilterPlaneDistance
 
double m_lambdaShort
 
int m_numFloorPoints
 
int m_numNonFloorPoints
 
double m_sigmaHit
 
double m_zHit
 
double m_zMax
 
double m_zRand
 
double m_zShort
 
- Protected Attributes inherited from humanoid_localization::ObservationModel
boost::shared_ptr< octomap::OcTreem_map
 
boost::shared_ptr< MapModelm_mapModel
 
ros::Publisher m_pc_pub
 
EngineT m_rngEngine
 
NormalGeneratorT m_rngNormal
 
UniformGeneratorT m_rngUniform
 
double m_sigmaPitch
 
double m_sigmaRoll
 
double m_sigmaZ
 
bool m_use_squared_error
 
double m_weightPitch
 
double m_weightRoll
 
double m_weightZ
 

Additional Inherited Members

- Static Public Member Functions inherited from humanoid_localization::ObservationModel
static double logLikelihood (double x, double sigma)
 Helper function to compute the log likelihood. More...
 
static double logLikelihoodSq (double x_sq, double sigma)
 Helper function to compute the log likelihood based on sqared distances. More...
 

Detailed Description

Definition at line 41 of file RaycastingModel.h.

Constructor & Destructor Documentation

humanoid_localization::RaycastingModel::RaycastingModel ( ros::NodeHandle nh,
boost::shared_ptr< MapModel mapModel,
EngineT rngEngine 
)

Definition at line 30 of file RaycastingModel.cpp.

humanoid_localization::RaycastingModel::~RaycastingModel ( )
virtual

Definition at line 57 of file RaycastingModel.cpp.

Member Function Documentation

bool humanoid_localization::RaycastingModel::getHeightError ( const Particle p,
const tf::StampedTransform footprintToBase,
double &  heightError 
) const
protectedvirtual

Implements humanoid_localization::ObservationModel.

Definition at line 136 of file RaycastingModel.cpp.

void humanoid_localization::RaycastingModel::integrateMeasurement ( Particles particles,
const PointCloud pc,
const std::vector< float > &  ranges,
float  max_range,
const tf::Transform baseToSensor 
)
virtual

Integrate a measurement in particle set, update weights accordingly Particle weights should be in log scale before, weights are added.

Implements humanoid_localization::ObservationModel.

Definition at line 61 of file RaycastingModel.cpp.

Member Data Documentation

bool humanoid_localization::RaycastingModel::m_filterPointCloudGround
protected

Definition at line 57 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_groundFilterAngle
protected

Definition at line 59 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_groundFilterDistance
protected

Definition at line 58 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_groundFilterPlaneDistance
protected

Definition at line 60 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_lambdaShort
protected

Definition at line 55 of file RaycastingModel.h.

int humanoid_localization::RaycastingModel::m_numFloorPoints
protected

Definition at line 61 of file RaycastingModel.h.

int humanoid_localization::RaycastingModel::m_numNonFloorPoints
protected

Definition at line 62 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_sigmaHit
protected

Definition at line 54 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_zHit
protected

Definition at line 50 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_zMax
protected

Definition at line 53 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_zRand
protected

Definition at line 51 of file RaycastingModel.h.

double humanoid_localization::RaycastingModel::m_zShort
protected

Definition at line 52 of file RaycastingModel.h.


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


humanoid_localization
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Mon Jun 10 2019 13:38:31