Public Member Functions | Protected Attributes | List of all members
PositionFilter Class Reference

Estimator specialized in estimating the position of a target. The estimator uses a Kalman filter with constant velocity process model. If no updates are received for a given amount of time, the PositionFilter replaces the Kalman filter output by a predefined Gaussian distribution over the current state of the filter (to avoid unrealistic propagation of the state). More...

#include <PositionFilter.h>

Inheritance diagram for PositionFilter:
Inheritance graph
[legend]

Public Member Functions

virtual PositionFilterclone () const
 
const pbl::PDFgetValue () const
 Returns the current estimated state value. More...
 
 PositionFilter ()
 
 PositionFilter (const PositionFilter &orig)
 
virtual void propagate (const mhf::Time &time)
 Propagates the internal state to Time time. More...
 
virtual void reset ()
 Resets the internal state of the estimator to its initial value. More...
 
bool setParameter (const std::string &param, bool b)
 Set a boolean parameter of this state estimator. More...
 
bool setParameter (const std::string &param, double v)
 Set a real-valued parameter of this state estimator. More...
 
void setValue (const pbl::PDF &pdf)
 
void update (const pbl::PDF &z, const mhf::Time &time)
 Updates the internal state based on measurement z. More...
 
virtual ~PositionFilter ()
 
- Public Member Functions inherited from mhf::IStateEstimator
virtual bool setParameter (const std::string &param, const std::string &s)
 
virtual ~IStateEstimator ()
 

Protected Attributes

pbl::Gaussianfixed_pdf_
 
double fixed_pdf_cov_
 
KalmanFilterkalman_filter_
 
double kalman_timeout_
 
double max_acceleration_
 
mhf::Time t_last_propagation_
 
mhf::Time t_last_update_
 

Detailed Description

Estimator specialized in estimating the position of a target. The estimator uses a Kalman filter with constant velocity process model. If no updates are received for a given amount of time, the PositionFilter replaces the Kalman filter output by a predefined Gaussian distribution over the current state of the filter (to avoid unrealistic propagation of the state).

Definition at line 52 of file PositionFilter.h.

Constructor & Destructor Documentation

PositionFilter::PositionFilter ( )

Definition at line 40 of file PositionFilter.cpp.

PositionFilter::PositionFilter ( const PositionFilter orig)

Definition at line 44 of file PositionFilter.cpp.

PositionFilter::~PositionFilter ( )
virtual

Definition at line 57 of file PositionFilter.cpp.

Member Function Documentation

PositionFilter * PositionFilter::clone ( ) const
virtual

Implements mhf::IStateEstimator.

Definition at line 62 of file PositionFilter.cpp.

const pbl::PDF & PositionFilter::getValue ( ) const
virtual

Returns the current estimated state value.

Returns
The current state, i.e., the current attribute value represented as probability density function

Implements mhf::IStateEstimator.

Definition at line 137 of file PositionFilter.cpp.

void PositionFilter::propagate ( const mhf::Time time)
virtual

Propagates the internal state to Time time.

Parameters
timeThe time to which the internal state is propagated

Implements mhf::IStateEstimator.

Definition at line 66 of file PositionFilter.cpp.

void PositionFilter::reset ( )
virtual

Resets the internal state of the estimator to its initial value.

Implements mhf::IStateEstimator.

Definition at line 129 of file PositionFilter.cpp.

bool PositionFilter::setParameter ( const std::string &  param,
bool  b 
)
virtual

Set a boolean parameter of this state estimator.

Parameters
paramThe parameter name
bThe boolean value
Returns
Returns true if the parameter was known to the estimator; false otherwise

Reimplemented from mhf::IStateEstimator.

Definition at line 147 of file PositionFilter.cpp.

bool PositionFilter::setParameter ( const std::string &  param,
double  v 
)
virtual

Set a real-valued parameter of this state estimator.

Parameters
paramThe parameter name
vThe float value
Returns
Returns true if the parameter was known to the estimator; false otherwise

Reimplemented from mhf::IStateEstimator.

Definition at line 151 of file PositionFilter.cpp.

void PositionFilter::setValue ( const pbl::PDF pdf)
void PositionFilter::update ( const pbl::PDF z,
const mhf::Time time 
)
virtual

Updates the internal state based on measurement z.

Parameters
zThe measurement with which to update, represented as a probability density function
timeThe time to which the internal state is propagated before updating

Implements mhf::IStateEstimator.

Definition at line 111 of file PositionFilter.cpp.

Member Data Documentation

pbl::Gaussian* PositionFilter::fixed_pdf_
protected

Definition at line 114 of file PositionFilter.h.

double PositionFilter::fixed_pdf_cov_
protected

Definition at line 120 of file PositionFilter.h.

KalmanFilter* PositionFilter::kalman_filter_
protected

Definition at line 112 of file PositionFilter.h.

double PositionFilter::kalman_timeout_
protected

Definition at line 122 of file PositionFilter.h.

double PositionFilter::max_acceleration_
protected

Definition at line 118 of file PositionFilter.h.

mhf::Time PositionFilter::t_last_propagation_
protected

Definition at line 110 of file PositionFilter.h.

mhf::Time PositionFilter::t_last_update_
protected

Definition at line 108 of file PositionFilter.h.


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


wire_state_estimators
Author(s): Sjoerd van den Dries, Jos Elfring
autogenerated on Fri Apr 16 2021 02:32:34