#include <RaycastingModel.h>
|
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 () |
|
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 () |
|
Definition at line 41 of file RaycastingModel.h.
humanoid_localization::RaycastingModel::~RaycastingModel |
( |
| ) |
|
|
virtual |
bool humanoid_localization::RaycastingModel::getHeightError |
( |
const Particle & |
p, |
|
|
const tf::StampedTransform & |
footprintToBase, |
|
|
double & |
heightError |
|
) |
| const |
|
protectedvirtual |
void humanoid_localization::RaycastingModel::integrateMeasurement |
( |
Particles & |
particles, |
|
|
const PointCloud & |
pc, |
|
|
const std::vector< float > & |
ranges, |
|
|
float |
max_range, |
|
|
const tf::Transform & |
baseToSensor |
|
) |
| |
|
virtual |
bool humanoid_localization::RaycastingModel::m_filterPointCloudGround |
|
protected |
double humanoid_localization::RaycastingModel::m_groundFilterAngle |
|
protected |
double humanoid_localization::RaycastingModel::m_groundFilterDistance |
|
protected |
double humanoid_localization::RaycastingModel::m_groundFilterPlaneDistance |
|
protected |
double humanoid_localization::RaycastingModel::m_lambdaShort |
|
protected |
int humanoid_localization::RaycastingModel::m_numFloorPoints |
|
protected |
int humanoid_localization::RaycastingModel::m_numNonFloorPoints |
|
protected |
double humanoid_localization::RaycastingModel::m_sigmaHit |
|
protected |
double humanoid_localization::RaycastingModel::m_zHit |
|
protected |
double humanoid_localization::RaycastingModel::m_zMax |
|
protected |
double humanoid_localization::RaycastingModel::m_zRand |
|
protected |
double humanoid_localization::RaycastingModel::m_zShort |
|
protected |
The documentation for this class was generated from the following files: