Public Member Functions | Protected Attributes | List of all members
hector_pose_estimation::GroundVehicleModel Class Reference

#include <ground_vehicle_model.h>

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

Public Member Functions

virtual void getDerivative (StateVector &x_dot, const State &state)
 
virtual void getPrior (State &state)
 
virtual void getStateJacobian (SystemMatrix &A, const State &state, bool init=true)
 
virtual SystemStatus getStatusFlags (const State &state)
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GroundVehicleModel ()
 
virtual bool limitState (State &state)
 
virtual ~GroundVehicleModel ()
 
- Public Member Functions inherited from hector_pose_estimation::GenericQuaternionSystemModel
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GenericQuaternionSystemModel ()
 
virtual void getSystemNoise (NoiseVariance &Q, const State &state, bool init=true)
 
virtual bool init (PoseEstimation &estimator, System &system, State &state)
 
bool prepareUpdate (State &state, double dt)
 
virtual ~GenericQuaternionSystemModel ()
 
- Public Member Functions inherited from hector_pose_estimation::TimeContinuousSystemModel_< GenericQuaternionSystemModel >
void getExpectedDiff (StateVector &x_diff, const State &state, double dt)
 
virtual void getInputJacobian (InputMatrix &B, const State &state, bool init=true)
 
void getInputJacobian (InputMatrix &B, const State &state, double dt, bool init=true)
 
void getStateJacobian (SystemMatrix &A, const State &state, double dt, bool init=true)
 
void getSystemNoise (NoiseVariance &Q, const State &state, double dt, bool init=true)
 
virtual SystemModel::SystemTypeEnum getSystemType () const
 
 TimeContinuousSystemModel_ ()
 
virtual ~TimeContinuousSystemModel_ ()
 
- Public Member Functions inherited from hector_pose_estimation::SystemModel_< GenericQuaternionSystemModel, Dynamic, Dynamic >
GenericQuaternionSystemModelderived ()
 
const GenericQuaternionSystemModelderived () const
 
virtual ~SystemModel_ ()
 
- Public Member Functions inherited from hector_pose_estimation::SystemModel
virtual bool active (const State &state)
 
virtual void afterUpdate (State &state)
 
virtual ~SystemModel ()
 
- Public Member Functions inherited from hector_pose_estimation::Model
virtual void cleanup ()
 
ParameterListparameters ()
 
const ParameterListparameters () const
 
virtual void reset (State &state)
 
virtual ~Model ()
 

Protected Attributes

double base_height_
 
Matrix_< 3, 3 >::type dR3
 
double gain_
 
double max_height_
 
double min_height_
 
- Protected Attributes inherited from hector_pose_estimation::GenericQuaternionSystemModel
ColumnVector3 acceleration_nav_
 
double acceleration_stddev_
 
boost::shared_ptr< Accelerometeraccelerometer_
 
double angular_acceleration_stddev_
 
ForceInput::Ptr force_input_
 
AliasT< double > gravity_
 
boost::shared_ptr< Gyrogyro_
 
boost::shared_ptr< ImuInputimu_
 
RateInput::Ptr rate_input_
 
ColumnVector3 rate_nav_
 
double rate_stddev_
 
TorqueInput::Ptr torque_input_
 
double velocity_stddev_
 
- Protected Attributes inherited from hector_pose_estimation::Model
ParameterList parameters_
 

Additional Inherited Members

- Public Types inherited from hector_pose_estimation::SystemModel
enum  SystemTypeEnum { UNKNOWN_SYSTEM_TYPE, TIME_DISCRETE, TIME_CONTINUOUS }
 
- Protected Types inherited from hector_pose_estimation::GenericQuaternionSystemModel
typedef Input_< 3 > ForceInput
 
typedef Input_< 3 > RateInput
 
typedef Input_< 3 > TorqueInput
 

Detailed Description

Definition at line 48 of file ground_vehicle_model.h.

Constructor & Destructor Documentation

hector_pose_estimation::GroundVehicleModel::GroundVehicleModel ( )

Definition at line 39 of file ground_vehicle_model.cpp.

hector_pose_estimation::GroundVehicleModel::~GroundVehicleModel ( )
virtual

Definition at line 57 of file ground_vehicle_model.cpp.

Member Function Documentation

void hector_pose_estimation::GroundVehicleModel::getDerivative ( StateVector &  x_dot,
const State state 
)
virtual

Reimplemented from hector_pose_estimation::GenericQuaternionSystemModel.

Definition at line 67 of file ground_vehicle_model.cpp.

void hector_pose_estimation::GroundVehicleModel::getPrior ( State state)
virtual

Reimplemented from hector_pose_estimation::GenericQuaternionSystemModel.

Definition at line 61 of file ground_vehicle_model.cpp.

void hector_pose_estimation::GroundVehicleModel::getStateJacobian ( SystemMatrix &  A,
const State state,
bool  init = true 
)
virtual

Reimplemented from hector_pose_estimation::GenericQuaternionSystemModel.

Definition at line 82 of file ground_vehicle_model.cpp.

SystemStatus hector_pose_estimation::GroundVehicleModel::getStatusFlags ( const State state)
virtual

Reimplemented from hector_pose_estimation::GenericQuaternionSystemModel.

Definition at line 98 of file ground_vehicle_model.cpp.

bool hector_pose_estimation::GroundVehicleModel::limitState ( State state)
virtual

Reimplemented from hector_pose_estimation::SystemModel.

Definition at line 108 of file ground_vehicle_model.cpp.

Member Data Documentation

double hector_pose_estimation::GroundVehicleModel::base_height_
protected

Definition at line 68 of file ground_vehicle_model.h.

Matrix_<3,3>::type hector_pose_estimation::GroundVehicleModel::dR3
protected

Definition at line 69 of file ground_vehicle_model.h.

double hector_pose_estimation::GroundVehicleModel::gain_
protected

Definition at line 67 of file ground_vehicle_model.h.

double hector_pose_estimation::GroundVehicleModel::max_height_
protected

Definition at line 68 of file ground_vehicle_model.h.

double hector_pose_estimation::GroundVehicleModel::min_height_
protected

Definition at line 68 of file ground_vehicle_model.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