$search
#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 () |
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 |
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.
| humanoid_localization::EndpointModel::~EndpointModel | ( | ) | [virtual] |
Definition at line 45 of file EndpointModel.cpp.
| bool humanoid_localization::EndpointModel::getHeightError | ( | const Particle & | p, | |
| const tf::StampedTransform & | footprintToBase, | |||
| double & | heightError | |||
| ) | const [protected, virtual] |
Implements humanoid_localization::ObservationModel.
Definition at line 77 of file EndpointModel.cpp.
| void humanoid_localization::EndpointModel::initDistanceMap | ( | ) | [protected] |
Definition at line 103 of file EndpointModel.cpp.
| void humanoid_localization::EndpointModel::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 49 of file EndpointModel.cpp.
| void humanoid_localization::EndpointModel::setMap | ( | boost::shared_ptr< octomap::OcTree > | map | ) | [virtual] |
Reimplemented from humanoid_localization::ObservationModel.
Definition at line 98 of file EndpointModel.cpp.
boost::shared_ptr<DynamicEDTOctomap> humanoid_localization::EndpointModel::m_distanceMap [protected] |
Definition at line 55 of file EndpointModel.h.
double humanoid_localization::EndpointModel::m_maxObstacleDistance [protected] |
Definition at line 54 of file EndpointModel.h.
double humanoid_localization::EndpointModel::m_sigma [protected] |
Definition at line 53 of file EndpointModel.h.