Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
rosflight_firmware::Estimator Class Reference

#include <estimator.h>

Inheritance diagram for rosflight_firmware::Estimator:
Inheritance graph
[legend]

Classes

struct  State
 

Public Member Functions

const turbomath::VectoraccLPF ()
 
const turbomath::Vectorbias ()
 
 Estimator (ROSflight &_rf)
 
const turbomath::VectorgyroLPF ()
 
void init ()
 
void param_change_callback (uint16_t param_id) override
 
void reset_adaptive_bias ()
 
void reset_state ()
 
void run ()
 
void set_external_attitude_update (const turbomath::Quaternion &q)
 
const Statestate () const
 

Private Member Functions

turbomath::Vector accel_correction () const
 
bool can_use_accel () const
 
bool can_use_extatt () const
 
turbomath::Vector extatt_correction () const
 
void integrate_angular_rate (turbomath::Quaternion &quat, const turbomath::Vector &omega, const float dt) const
 
void quaternion_to_dcm (const turbomath::Quaternion &q, turbomath::Vector &X, turbomath::Vector &Y, turbomath::Vector &Z) const
 
void run_LPF ()
 
turbomath::Vector smoothed_gyro_measurement ()
 

Private Attributes

turbomath::Vector accel_LPF_
 
turbomath::Vector bias_
 
bool extatt_update_next_run_
 
const turbomath::Vector g_ = {0.0f, 0.0f, -1.0f}
 
turbomath::Vector gyro_LPF_
 
uint64_t last_acc_update_us_
 
uint64_t last_extatt_update_us_
 
uint64_t last_time_
 
turbomath::Quaternion q_extatt_
 
ROSflightRF_
 
State state_
 
turbomath::Vector w1_
 
turbomath::Vector w2_
 
turbomath::Vector w_acc_
 

Detailed Description

Definition at line 47 of file estimator.h.

Constructor & Destructor Documentation

rosflight_firmware::Estimator::Estimator ( ROSflight _rf)

Definition at line 38 of file estimator.cpp.

Member Function Documentation

turbomath::Vector rosflight_firmware::Estimator::accel_correction ( ) const
private

Definition at line 270 of file estimator.cpp.

const turbomath::Vector& rosflight_firmware::Estimator::accLPF ( )
inline

Definition at line 66 of file estimator.h.

const turbomath::Vector& rosflight_firmware::Estimator::bias ( )
inline

Definition at line 64 of file estimator.h.

bool rosflight_firmware::Estimator::can_use_accel ( ) const
private

Definition at line 242 of file estimator.cpp.

bool rosflight_firmware::Estimator::can_use_extatt ( ) const
private

Definition at line 265 of file estimator.cpp.

turbomath::Vector rosflight_firmware::Estimator::extatt_correction ( ) const
private

Definition at line 293 of file estimator.cpp.

const turbomath::Vector& rosflight_firmware::Estimator::gyroLPF ( )
inline

Definition at line 68 of file estimator.h.

void rosflight_firmware::Estimator::init ( )

Definition at line 90 of file estimator.cpp.

void rosflight_firmware::Estimator::integrate_angular_rate ( turbomath::Quaternion quat,
const turbomath::Vector omega,
const float  dt 
) const
private

Definition at line 335 of file estimator.cpp.

void rosflight_firmware::Estimator::param_change_callback ( uint16_t  param_id)
overridevirtual

Implements rosflight_firmware::ParamListenerInterface.

Definition at line 98 of file estimator.cpp.

void rosflight_firmware::Estimator::quaternion_to_dcm ( const turbomath::Quaternion q,
turbomath::Vector X,
turbomath::Vector Y,
turbomath::Vector Z 
) const
private

Definition at line 378 of file estimator.cpp.

void rosflight_firmware::Estimator::reset_adaptive_bias ( )

Definition at line 83 of file estimator.cpp.

void rosflight_firmware::Estimator::reset_state ( )

Definition at line 40 of file estimator.cpp.

void rosflight_firmware::Estimator::run ( )

Definition at line 125 of file estimator.cpp.

void rosflight_firmware::Estimator::run_LPF ( )
private

Definition at line 103 of file estimator.cpp.

void rosflight_firmware::Estimator::set_external_attitude_update ( const turbomath::Quaternion q)

Definition at line 119 of file estimator.cpp.

turbomath::Vector rosflight_firmware::Estimator::smoothed_gyro_measurement ( )
private

Definition at line 316 of file estimator.cpp.

const State& rosflight_firmware::Estimator::state ( ) const
inline

Definition at line 62 of file estimator.h.

Member Data Documentation

turbomath::Vector rosflight_firmware::Estimator::accel_LPF_
private

Definition at line 92 of file estimator.h.

turbomath::Vector rosflight_firmware::Estimator::bias_
private

Definition at line 90 of file estimator.h.

bool rosflight_firmware::Estimator::extatt_update_next_run_
private

Definition at line 97 of file estimator.h.

const turbomath::Vector rosflight_firmware::Estimator::g_ = {0.0f, 0.0f, -1.0f}
private

Definition at line 78 of file estimator.h.

turbomath::Vector rosflight_firmware::Estimator::gyro_LPF_
private

Definition at line 93 of file estimator.h.

uint64_t rosflight_firmware::Estimator::last_acc_update_us_
private

Definition at line 84 of file estimator.h.

uint64_t rosflight_firmware::Estimator::last_extatt_update_us_
private

Definition at line 85 of file estimator.h.

uint64_t rosflight_firmware::Estimator::last_time_
private

Definition at line 83 of file estimator.h.

turbomath::Quaternion rosflight_firmware::Estimator::q_extatt_
private

Definition at line 98 of file estimator.h.

ROSflight& rosflight_firmware::Estimator::RF_
private

Definition at line 80 of file estimator.h.

State rosflight_firmware::Estimator::state_
private

Definition at line 81 of file estimator.h.

turbomath::Vector rosflight_firmware::Estimator::w1_
private

Definition at line 87 of file estimator.h.

turbomath::Vector rosflight_firmware::Estimator::w2_
private

Definition at line 88 of file estimator.h.

turbomath::Vector rosflight_firmware::Estimator::w_acc_
private

Definition at line 95 of file estimator.h.


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


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:58