Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
hector_pose_estimation::PoseUpdate Class Reference

#include <poseupdate.h>

Inheritance diagram for hector_pose_estimation::PoseUpdate:
Inheritance graph
[legend]

Classes

class  Update
 

Public Member Functions

 PoseUpdate (const std::string &name="poseupdate")
 
virtual bool updateImpl (const MeasurementUpdate &update)
 
virtual ~PoseUpdate ()
 
- Public Member Functions inherited from hector_pose_estimation::Measurement
virtual bool active (const State &state)
 
virtual void add (const MeasurementUpdate &update)
 
virtual void cleanup ()
 
void disable ()
 
void enable ()
 
bool enabled () const
 
virtual Filterfilter () const
 
virtual int getDimension () const
 
double getMinInterval () const
 
virtual MeasurementModelgetModel () const
 
virtual const std::string & getName () const
 
virtual SystemStatus getStatusFlags () const
 
double getTimeout () const
 
void increase_timer (double dt)
 
virtual bool init (PoseEstimation &estimator, State &state)
 
 Measurement (const std::string &name)
 
virtual ParameterListparameters ()
 
virtual const ParameterListparameters () const
 
virtual bool process ()
 
virtual void reset (State &state)
 
virtual void setFilter (Filter *filter)
 
void setMinInterval (double min_interval)
 
void setName (const std::string &name)
 
void setTimeout (double timeout)
 
bool timedout () const
 
virtual bool update (const MeasurementUpdate &update)
 
virtual ~Measurement ()
 

Protected Member Functions

virtual Queuequeue ()
 
- Protected Member Functions inherited from hector_pose_estimation::Measurement
virtual void onCleanup ()
 
virtual bool onInit (PoseEstimation &estimator)
 
virtual void onReset ()
 

Protected Attributes

Queue_< Updatequeue_
 
- Protected Attributes inherited from hector_pose_estimation::Measurement
bool enabled_
 
Filterfilter_
 
double min_interval_
 
std::string name_
 
ParameterList parameters_
 
SystemStatus status_flags_
 
double timeout_
 
double timer_
 

Private Types

typedef boost::function< void(State &state, const ColumnVector &diff)> JumpFunction
 

Private Member Functions

double calculateOmega (const SymmetricMatrix &Ix, const SymmetricMatrix &Iy)
 
template<typename MeasurementVector , typename MeasurementMatrix , typename NoiseVariance >
double updateInternal (State &state, const NoiseVariance &Iy, const MeasurementVector &error, const MeasurementMatrix &H, const std::string &text, const double max_error=0.0, JumpFunction jump_function=JumpFunction())
 

Private Attributes

double fixed_alpha_
 
double fixed_angular_rate_xy_stddev_
 
double fixed_angular_rate_z_stddev_
 
double fixed_beta_
 
double fixed_position_xy_stddev_
 
double fixed_position_z_stddev_
 
double fixed_velocity_xy_stddev_
 
double fixed_velocity_z_stddev_
 
double fixed_yaw_stddev_
 
bool interpret_covariance_as_information_matrix_
 
bool jump_on_max_error_
 
double max_angular_rate_xy_error_
 
double max_angular_rate_z_error_
 
double max_position_xy_error_
 
double max_position_z_error_
 
double max_time_difference_
 
double max_velocity_xy_error_
 
double max_velocity_z_error_
 
double max_yaw_error_
 
PositionXYModel position_xy_model_
 
PositionZModel position_z_model_
 
bool predict_pose_
 
TwistModel twist_model_
 
YawModel yaw_model_
 

Additional Inherited Members

- Static Public Member Functions inherited from hector_pose_estimation::Measurement
template<class ConcreteModel >
static boost::shared_ptr< Measurement_< ConcreteModel > > create (ConcreteModel *model, const std::string &name)
 

Detailed Description

Definition at line 82 of file poseupdate.h.

Member Typedef Documentation

typedef boost::function<void(State &state, const ColumnVector &diff)> hector_pose_estimation::PoseUpdate::JumpFunction
private

Definition at line 133 of file poseupdate.h.

Constructor & Destructor Documentation

hector_pose_estimation::PoseUpdate::PoseUpdate ( const std::string &  name = "poseupdate")

Definition at line 38 of file poseupdate.cpp.

hector_pose_estimation::PoseUpdate::~PoseUpdate ( )
virtual

Definition at line 91 of file poseupdate.cpp.

Member Function Documentation

double hector_pose_estimation::PoseUpdate::calculateOmega ( const SymmetricMatrix Ix,
const SymmetricMatrix Iy 
)
private

Definition at line 352 of file poseupdate.cpp.

virtual Queue& hector_pose_estimation::PoseUpdate::queue ( )
inlineprotectedvirtual

Implements hector_pose_estimation::Measurement.

Definition at line 141 of file poseupdate.h.

bool hector_pose_estimation::PoseUpdate::updateImpl ( const MeasurementUpdate update)
virtual

Reimplemented from hector_pose_estimation::Measurement.

Definition at line 95 of file poseupdate.cpp.

template<typename MeasurementVector , typename MeasurementMatrix , typename NoiseVariance >
double hector_pose_estimation::PoseUpdate::updateInternal ( State state,
const NoiseVariance &  Iy,
const MeasurementVector &  error,
const MeasurementMatrix &  H,
const std::string &  text,
const double  max_error = 0.0,
JumpFunction  jump_function = JumpFunction() 
)
private

Definition at line 359 of file poseupdate.cpp.

Member Data Documentation

double hector_pose_estimation::PoseUpdate::fixed_alpha_
private

Definition at line 109 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_angular_rate_xy_stddev_
private

Definition at line 121 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_angular_rate_z_stddev_
private

Definition at line 122 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_beta_
private

Definition at line 109 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_position_xy_stddev_
private

Definition at line 115 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_position_z_stddev_
private

Definition at line 116 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_velocity_xy_stddev_
private

Definition at line 119 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_velocity_z_stddev_
private

Definition at line 120 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::fixed_yaw_stddev_
private

Definition at line 117 of file poseupdate.h.

bool hector_pose_estimation::PoseUpdate::interpret_covariance_as_information_matrix_
private

Definition at line 110 of file poseupdate.h.

bool hector_pose_estimation::PoseUpdate::jump_on_max_error_
private

Definition at line 113 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_angular_rate_xy_error_
private

Definition at line 130 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_angular_rate_z_error_
private

Definition at line 131 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_position_xy_error_
private

Definition at line 124 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_position_z_error_
private

Definition at line 125 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_time_difference_
private

Definition at line 111 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_velocity_xy_error_
private

Definition at line 128 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_velocity_z_error_
private

Definition at line 129 of file poseupdate.h.

double hector_pose_estimation::PoseUpdate::max_yaw_error_
private

Definition at line 126 of file poseupdate.h.

PositionXYModel hector_pose_estimation::PoseUpdate::position_xy_model_
private

Definition at line 104 of file poseupdate.h.

PositionZModel hector_pose_estimation::PoseUpdate::position_z_model_
private

Definition at line 105 of file poseupdate.h.

bool hector_pose_estimation::PoseUpdate::predict_pose_
private

Definition at line 112 of file poseupdate.h.

Queue_<Update> hector_pose_estimation::PoseUpdate::queue_
protected

Definition at line 140 of file poseupdate.h.

TwistModel hector_pose_estimation::PoseUpdate::twist_model_
private

Definition at line 107 of file poseupdate.h.

YawModel hector_pose_estimation::PoseUpdate::yaw_model_
private

Definition at line 106 of file poseupdate.h.


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


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:31