Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
humanoid_localization::EndpointModel Class Reference

#include <EndpointModel.h>

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

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< DynamicEDTOctomapm_distanceMap
 
double m_maxObstacleDistance
 
double m_sigma
 
- Protected Attributes inherited from humanoid_localization::ObservationModel
boost::shared_ptr< octomap::OcTreem_map
 
boost::shared_ptr< MapModelm_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...
 

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.

humanoid_localization::EndpointModel::~EndpointModel ( )
virtual

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
protectedvirtual

Implements humanoid_localization::ObservationModel.

Definition at line 80 of file EndpointModel.cpp.

void humanoid_localization::EndpointModel::initDistanceMap ( )
protected

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.

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.


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


humanoid_localization
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Mon Jun 10 2019 13:38:31