Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
humanoid_localization::ObservationModel Class Referenceabstract

#include <ObservationModel.h>

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

Public Member Functions

virtual void integrateMeasurement (Particles &particles, const PointCloud &pc, const std::vector< float > &ranges, float max_range, const tf::Transform &baseToSensor)=0
 
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 ()
 

Static Public Member Functions

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...
 

Protected Member Functions

virtual bool getHeightError (const Particle &p, const tf::StampedTransform &footprintToBase, double &heightError) const =0
 

Protected Attributes

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
 

Detailed Description

Definition at line 51 of file ObservationModel.h.

Constructor & Destructor Documentation

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

Definition at line 31 of file ObservationModel.cpp.

humanoid_localization::ObservationModel::~ObservationModel ( )
virtual

Definition at line 55 of file ObservationModel.cpp.

Member Function Documentation

virtual bool humanoid_localization::ObservationModel::getHeightError ( const Particle p,
const tf::StampedTransform footprintToBase,
double &  heightError 
) const
protectedpure virtual
virtual void humanoid_localization::ObservationModel::integrateMeasurement ( Particles particles,
const PointCloud pc,
const std::vector< float > &  ranges,
float  max_range,
const tf::Transform baseToSensor 
)
pure virtual

Integrate a measurement in particle set, update weights accordingly Particle weights should be in log scale before, weights are added.

Implemented in humanoid_localization::EndpointModel, and humanoid_localization::RaycastingModel.

void humanoid_localization::ObservationModel::integratePoseMeasurement ( Particles particles,
double  roll,
double  pitch,
const tf::StampedTransform footprintToTorso 
)
virtual

Definition at line 58 of file ObservationModel.cpp.

static double humanoid_localization::ObservationModel::logLikelihood ( double  x,
double  sigma 
)
inlinestatic

Helper function to compute the log likelihood.

Definition at line 57 of file ObservationModel.h.

static double humanoid_localization::ObservationModel::logLikelihoodSq ( double  x_sq,
double  sigma 
)
inlinestatic

Helper function to compute the log likelihood based on sqared distances.

Definition at line 63 of file ObservationModel.h.

void humanoid_localization::ObservationModel::setMap ( boost::shared_ptr< octomap::OcTree map)
virtual

Reimplemented in humanoid_localization::EndpointModel.

Definition at line 81 of file ObservationModel.cpp.

Member Data Documentation

boost::shared_ptr<octomap::OcTree> humanoid_localization::ObservationModel::m_map
protected

Definition at line 88 of file ObservationModel.h.

boost::shared_ptr<MapModel> humanoid_localization::ObservationModel::m_mapModel
protected

Definition at line 84 of file ObservationModel.h.

ros::Publisher humanoid_localization::ObservationModel::m_pc_pub
protected

Definition at line 89 of file ObservationModel.h.

EngineT humanoid_localization::ObservationModel::m_rngEngine
protected

Definition at line 85 of file ObservationModel.h.

NormalGeneratorT humanoid_localization::ObservationModel::m_rngNormal
protected

Definition at line 86 of file ObservationModel.h.

UniformGeneratorT humanoid_localization::ObservationModel::m_rngUniform
protected

Definition at line 87 of file ObservationModel.h.

double humanoid_localization::ObservationModel::m_sigmaPitch
protected

Definition at line 97 of file ObservationModel.h.

double humanoid_localization::ObservationModel::m_sigmaRoll
protected

Definition at line 96 of file ObservationModel.h.

double humanoid_localization::ObservationModel::m_sigmaZ
protected

Definition at line 95 of file ObservationModel.h.

bool humanoid_localization::ObservationModel::m_use_squared_error
protected

Definition at line 99 of file ObservationModel.h.

double humanoid_localization::ObservationModel::m_weightPitch
protected

Definition at line 92 of file ObservationModel.h.

double humanoid_localization::ObservationModel::m_weightRoll
protected

Definition at line 91 of file ObservationModel.h.

double humanoid_localization::ObservationModel::m_weightZ
protected

Definition at line 93 of file ObservationModel.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