#include <EndpointModel.h>

Public Member Functions | |
| EndpointModel (ros::NodeHandle *nh, boost::shared_ptr< MapModel > mapModel, EngineT *rngEngine) | |
| virtual void | integrateMeasurement (Particles &particles, const PointCloud &pc, const std::vector< float > &ranges, float max_range, const tf::Transform &baseToSensor) |
| virtual void | setMap (boost::shared_ptr< octomap::OcTree > map) |
| virtual | ~EndpointModel () |
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 | ~ObservationModel () |
Protected Member Functions | |
| bool | getHeightError (const Particle &p, const tf::StampedTransform &footprintToBase, double &heightError) const |
| void | initDistanceMap () |
Protected Attributes | |
| boost::shared_ptr< DynamicEDTOctomap > | m_distanceMap |
| double | m_maxObstacleDistance |
| double | m_sigma |
Protected Attributes inherited from humanoid_localization::ObservationModel | |
| boost::shared_ptr< octomap::OcTree > | m_map |
| boost::shared_ptr< MapModel > | m_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... | |
Definition at line 42 of file EndpointModel.h.
| humanoid_localization::EndpointModel::EndpointModel | ( | ros::NodeHandle * | nh, |
| boost::shared_ptr< MapModel > | mapModel, | ||
| EngineT * | rngEngine | ||
| ) |
Definition at line 28 of file EndpointModel.cpp.
|
virtual |
Definition at line 45 of file EndpointModel.cpp.
|
protectedvirtual |
Implements humanoid_localization::ObservationModel.
Definition at line 80 of file EndpointModel.cpp.
|
protected |
Definition at line 107 of file EndpointModel.cpp.
|
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 49 of file EndpointModel.cpp.
|
virtual |
Reimplemented from humanoid_localization::ObservationModel.
Definition at line 102 of file EndpointModel.cpp.
|
protected |
Definition at line 55 of file EndpointModel.h.
|
protected |
Definition at line 54 of file EndpointModel.h.
|
protected |
Definition at line 53 of file EndpointModel.h.