#include <RaycastingModel.h>

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 () | 
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 | 
Definition at line 41 of file RaycastingModel.h.
| humanoid_localization::RaycastingModel::RaycastingModel | ( | ros::NodeHandle * | nh, | 
| boost::shared_ptr< MapModel > | mapModel, | ||
| EngineT * | rngEngine | ||
| ) | 
Definition at line 33 of file RaycastingModel.cpp.
| humanoid_localization::RaycastingModel::~RaycastingModel | ( | ) |  [virtual] | 
        
Definition at line 53 of file RaycastingModel.cpp.
| bool humanoid_localization::RaycastingModel::getHeightError | ( | const Particle & | p, | 
| const tf::StampedTransform & | footprintToBase, | ||
| double & | heightError | ||
| ) |  const [protected, virtual] | 
        
Implements humanoid_localization::ObservationModel.
Definition at line 132 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 57 of file RaycastingModel.cpp.
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.