Public Member Functions | Protected Member Functions | Protected Attributes
humanoid_localization::EndpointModel Class Reference

#include <EndpointModel.h>

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

List of all members.

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

Detailed Description

Definition at line 42 of file EndpointModel.h.


Constructor & Destructor Documentation

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

Definition at line 28 of file EndpointModel.cpp.

Definition at line 45 of file EndpointModel.cpp.


Member Function Documentation

bool humanoid_localization::EndpointModel::getHeightError ( const Particle p,
const tf::StampedTransform footprintToBase,
double &  heightError 
) const [protected, virtual]

Implements humanoid_localization::ObservationModel.

Definition at line 80 of file EndpointModel.cpp.

Definition at line 107 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 102 of file EndpointModel.cpp.


Member Data Documentation

boost::shared_ptr<DynamicEDTOctomap> humanoid_localization::EndpointModel::m_distanceMap [protected]

Definition at line 55 of file EndpointModel.h.

Definition at line 54 of file EndpointModel.h.

Definition at line 53 of file EndpointModel.h.


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


humanoid_localization
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Wed Aug 26 2015 11:54:40