APM:Libraries
Classes | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes | Static Private Attributes | Friends | List of all members
AP_AHRS Class Referenceabstract

#include <AP_AHRS.h>

Inheritance diagram for AP_AHRS:
[legend]
Collaboration diagram for AP_AHRS:
[legend]

Classes

struct  ahrs_flags
 

Public Member Functions

 AP_AHRS ()
 
virtual ~AP_AHRS ()
 
virtual void init ()
 
void set_fly_forward (bool b)
 
bool get_fly_forward (void) const
 
void set_likely_flying (bool b)
 
bool get_likely_flying (void) const
 
uint32_t get_time_flying_ms (void) const
 
AHRS_VehicleClass get_vehicle_class (void) const
 
void set_vehicle_class (AHRS_VehicleClass vclass)
 
void set_wind_estimation (bool b)
 
void set_compass (Compass *compass)
 
const Compassget_compass () const
 
void set_optflow (const OpticalFlow *optflow)
 
const OpticalFlowget_optflow () const
 
void set_orientation ()
 
void set_airspeed (AP_Airspeed *airspeed)
 
void set_beacon (AP_Beacon *beacon)
 
const AP_Airspeedget_airspeed (void) const
 
const AP_Beaconget_beacon (void) const
 
virtual uint8_t get_primary_accel_index (void) const
 
virtual uint8_t get_primary_gyro_index (void) const
 
virtual const Vector3fget_accel_ef (uint8_t i) const
 
virtual const Vector3fget_accel_ef (void) const
 
virtual const Vector3fget_accel_ef_blended (void) const
 
float get_yaw_rate_earth (void) const
 
virtual void update (bool skip_ins_update=false)=0
 
virtual const char * prearm_failure_reason (void) const
 
virtual bool have_ekf_logging (void) const
 
virtual const Vector3fget_gyro (void) const =0
 
Vector3f get_gyro_latest (void) const
 
virtual const Vector3fget_gyro_drift (void) const =0
 
virtual void reset_gyro_drift (void)=0
 
virtual void reset (bool recover_eulers=false)=0
 
virtual void reset_attitude (const float &roll, const float &pitch, const float &yaw)=0
 
virtual float get_error_rp (void) const =0
 
virtual float get_error_yaw (void) const =0
 
virtual const Matrix3fget_rotation_body_to_ned (void) const =0
 
const Matrix3fget_rotation_autopilot_body_to_vehicle_body (void) const
 
const Matrix3fget_rotation_vehicle_body_to_autopilot_body (void) const
 
virtual bool get_position (struct Location &loc) const =0
 
virtual bool get_hagl (float &height) const
 
virtual Vector3f wind_estimate (void) const =0
 
virtual bool airspeed_estimate (float *airspeed_ret) const
 
bool airspeed_estimate_true (float *airspeed_ret) const
 
float get_EAS2TAS (void) const
 
bool airspeed_sensor_enabled (void) const
 
virtual Vector2f groundspeed_vector (void)
 
virtual bool get_velocity_NED (Vector3f &vec) const
 
virtual bool get_expected_mag_field_NED (Vector3f &ret) const
 
virtual bool get_mag_field_correction (Vector3f &ret) const
 
virtual bool get_relative_position_NED_home (Vector3f &vec) const
 
virtual bool get_relative_position_NED_origin (Vector3f &vec) const
 
virtual bool get_relative_position_NE_home (Vector2f &vecNE) const
 
virtual bool get_relative_position_NE_origin (Vector2f &vecNE) const
 
virtual void get_relative_position_D_home (float &posD) const =0
 
virtual bool get_relative_position_D_origin (float &posD) const
 
float groundspeed (void)
 
virtual bool use_compass (void)
 
bool yaw_initialised (void) const
 
void set_correct_centrifugal (bool setting)
 
bool get_correct_centrifugal (void) const
 
const Vector3fget_trim () const
 
virtual void set_trim (Vector3f new_trim)
 
virtual void add_trim (float roll_in_radians, float pitch_in_radians, bool save_to_eeprom=true)
 
float cos_roll () const
 
float cos_pitch () const
 
float cos_yaw () const
 
float sin_roll () const
 
float sin_pitch () const
 
float sin_yaw () const
 
virtual bool get_secondary_attitude (Vector3f &eulers) const
 
virtual bool get_secondary_quaternion (Quaternion &quat) const
 
virtual bool get_secondary_position (struct Location &loc) const
 
const struct Locationget_home (void) const
 
void lock_home ()
 
bool home_is_locked () const
 
bool home_is_set (void) const
 
virtual void set_home (const Location &loc)=0
 
virtual bool set_origin (const Location &loc)
 
virtual bool get_origin (Location &ret) const
 
void Log_Write_Home_And_Origin ()
 
virtual bool have_inertial_nav (void) const
 
uint8_t get_active_accel_instance (void) const
 
virtual bool healthy (void) const =0
 
virtual bool initialised (void) const
 
virtual uint32_t getLastYawResetAngle (float &yawAng) const
 
virtual uint32_t getLastPosNorthEastReset (Vector2f &pos) const
 
virtual uint32_t getLastVelNorthEastReset (Vector2f &vel) const
 
virtual uint32_t getLastPosDownReset (float &posDelta) const
 
virtual bool resetHeightDatum (void)
 
virtual bool get_variances (float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
 
virtual uint32_t uptime_ms (void) const =0
 
int8_t get_ekf_type (void) const
 
virtual void getCorrectedDeltaVelocityNED (Vector3f &ret, float &dt) const
 
AP_AHRS_Viewcreate_view (enum Rotation rotation)
 
float getAOA (void)
 
float getSSA (void)
 
Vector2f rotate_earth_to_body2D (const Vector2f &ef_vector) const
 
Vector2f rotate_body_to_earth2D (const Vector2f &bf) const
 
virtual void update_AOA_SSA (void)
 
virtual bool get_hgt_ctrl_limit (float &limit) const
 
virtual void writeExtNavData (const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
 

Static Public Member Functions

static AP_AHRSget_singleton ()
 

Public Attributes

float roll
 
float pitch
 
float yaw
 
int32_t roll_sensor
 
int32_t pitch_sensor
 
int32_t yaw_sensor
 

Static Public Attributes

static const struct AP_Param::GroupInfo var_info []
 

Protected Member Functions

void calc_trig (const Matrix3f &rot, float &cr, float &cp, float &cy, float &sr, float &sp, float &sy) const
 
void update_trig (void)
 
void update_cd_values (void)
 

Protected Attributes

AHRS_VehicleClass _vehicle_class
 
AP_Float _kp_yaw
 
AP_Float _kp
 
AP_Float gps_gain
 
AP_Float beta
 
AP_Int8 _gps_use
 
AP_Int8 _wind_max
 
AP_Int8 _board_orientation
 
AP_Int8 _gps_minsats
 
AP_Int8 _gps_delay
 
AP_Int8 _ekf_type
 
AP_Float _custom_roll
 
AP_Float _custom_pitch
 
AP_Float _custom_yaw
 
Matrix3f _custom_rotation
 
struct AP_AHRS::ahrs_flags _flags
 
uint32_t _last_flying_ms
 
Compass_compass
 
const OpticalFlow_optflow
 
AP_Airspeed_airspeed
 
AP_Beacon_beacon
 
uint32_t _compass_last_update
 
AP_Vector3f _trim
 
Vector3f _last_trim
 
Matrix3f _rotation_autopilot_body_to_vehicle_body
 
Matrix3f _rotation_vehicle_body_to_autopilot_body
 
float _gyro_drift_limit
 
Vector3f _accel_ef [INS_MAX_INSTANCES]
 
Vector3f _accel_ef_blended
 
Vector2f _lp
 
Vector2f _hp
 
Vector2f _lastGndVelADS
 
struct Location _home
 
bool _home_is_set:1
 
bool _home_locked:1
 
float _cos_roll
 
float _cos_pitch
 
float _cos_yaw
 
float _sin_roll
 
float _sin_pitch
 
float _sin_yaw
 
uint8_t _active_accel_instance
 
AP_AHRS_View_view
 
float _AOA
 
float _SSA
 
uint32_t _last_AOA_update_ms
 

Static Private Attributes

static AP_AHRS_singleton
 

Friends

class AP_AHRS_View
 

Detailed Description

Definition at line 50 of file AP_AHRS.h.

Constructor & Destructor Documentation

◆ AP_AHRS()

AP_AHRS::AP_AHRS ( )
inline

Definition at line 56 of file AP_AHRS.h.

Here is the call graph for this function:

◆ ~AP_AHRS()

virtual AP_AHRS::~AP_AHRS ( )
inlinevirtual

Definition at line 80 of file AP_AHRS.h.

Member Function Documentation

◆ add_trim()

void AP_AHRS::add_trim ( float  roll_in_radians,
float  pitch_in_radians,
bool  save_to_eeprom = true 
)
virtual

Definition at line 199 of file AP_AHRS.cpp.

Referenced by get_trim().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ airspeed_estimate()

bool AP_AHRS::airspeed_estimate ( float *  airspeed_ret) const
virtual

Reimplemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.

Definition at line 170 of file AP_AHRS.cpp.

Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_RollController::_get_rate_out(), AP_TECS::_update_speed(), AP_AHRS_View::airspeed_estimate(), airspeed_estimate_true(), get_hagl(), AP_PitchController::get_rate_out(), AP_YawController::get_servo_out(), AP_Landing_Deepstall::override_servos(), and Variometer::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ airspeed_estimate_true()

bool AP_AHRS::airspeed_estimate_true ( float *  airspeed_ret) const
inline

Definition at line 281 of file AP_AHRS.h.

Referenced by AP_AHRS_View::airspeed_estimate_true(), and groundspeed_vector().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ airspeed_sensor_enabled()

bool AP_AHRS::airspeed_sensor_enabled ( void  ) const
inline

Definition at line 299 of file AP_AHRS.h.

Referenced by AP_TECS::_update_pitch(), AP_TECS::_update_speed(), AP_AHRS_DCM::airspeed_estimate(), airspeed_estimate(), NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::estimate_wind(), NavEKF3_core::setup_core(), AP_TECS::update_pitch_throttle(), NavEKF2_core::useAirspeed(), and NavEKF3_core::useAirspeed().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ calc_trig()

void AP_AHRS::calc_trig ( const Matrix3f rot,
float &  cr,
float &  cp,
float &  cy,
float &  sr,
float &  sp,
float &  sy 
) const
protected

Definition at line 290 of file AP_AHRS.cpp.

Referenced by AP_AHRS_View::update(), and update_trig().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ cos_pitch()

float AP_AHRS::cos_pitch ( ) const
inline

Definition at line 399 of file AP_AHRS.h.

◆ cos_roll()

float AP_AHRS::cos_roll ( ) const
inline

Definition at line 396 of file AP_AHRS.h.

◆ cos_yaw()

float AP_AHRS::cos_yaw ( ) const
inline

Definition at line 402 of file AP_AHRS.h.

Referenced by AC_Avoid::adjust_velocity_polygon(), and AR_AttitudeControl::get_forward_speed().

Here is the caller graph for this function:

◆ create_view()

AP_AHRS_View * AP_AHRS::create_view ( enum Rotation  rotation)

Definition at line 364 of file AP_AHRS.cpp.

Referenced by getCorrectedDeltaVelocityNED().

Here is the caller graph for this function:

◆ get_accel_ef() [1/2]

virtual const Vector3f& AP_AHRS::get_accel_ef ( uint8_t  i) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 193 of file AP_AHRS.h.

Referenced by AP_TECS::update_50hz().

Here is the caller graph for this function:

◆ get_accel_ef() [2/2]

virtual const Vector3f& AP_AHRS::get_accel_ef ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 196 of file AP_AHRS.h.

Referenced by AP_AHRS_NavEKF::get_accel_ef().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_ef_blended()

virtual const Vector3f& AP_AHRS::get_accel_ef_blended ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 201 of file AP_AHRS.h.

Referenced by AP_AHRS_NavEKF::get_accel_ef_blended(), AP_AHRS_View::get_accel_ef_blended(), and DataFlash_Class::Log_Write_Rate().

Here is the caller graph for this function:

◆ get_active_accel_instance()

uint8_t AP_AHRS::get_active_accel_instance ( void  ) const
inline

Definition at line 475 of file AP_AHRS.h.

Here is the call graph for this function:

◆ get_airspeed()

const AP_Airspeed* AP_AHRS::get_airspeed ( void  ) const
inline

Definition at line 174 of file AP_AHRS.h.

Referenced by AP_Arming::airspeed_checks(), AP_Frsky_Telem::calc_velandyaw(), NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), NavEKF2_core::readAirSpdData(), and NavEKF3_core::readAirSpdData().

Here is the caller graph for this function:

◆ get_beacon()

const AP_Beacon* AP_AHRS::get_beacon ( void  ) const
inline

Definition at line 178 of file AP_AHRS.h.

Referenced by DataFlash_Class::Log_Write_POS(), NavEKF2_core::readRngBcnData(), and NavEKF3_core::readRngBcnData().

Here is the caller graph for this function:

◆ get_compass()

const Compass* AP_AHRS::get_compass ( ) const
inline

◆ get_correct_centrifugal()

bool AP_AHRS::get_correct_centrifugal ( void  ) const
inline

Definition at line 380 of file AP_AHRS.h.

◆ get_EAS2TAS()

float AP_AHRS::get_EAS2TAS ( void  ) const
inline

Definition at line 290 of file AP_AHRS.h.

Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), AP_TECS::_update_speed(), AP_AHRS_DCM::airspeed_estimate(), airspeed_estimate(), airspeed_estimate_true(), AP_AHRS_DCM::estimate_wind(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), AP_AHRS_View::get_EAS2TAS(), AP_TECS::get_target_airspeed(), AP_L1_Control::loiter_radius(), NavEKF2_core::setWindMagStateLearningMode(), NavEKF3_core::setWindMagStateLearningMode(), and AP_L1_Control::turn_distance().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_ekf_type()

int8_t AP_AHRS::get_ekf_type ( void  ) const
inline

Definition at line 532 of file AP_AHRS.h.

◆ get_error_rp()

virtual float AP_AHRS::get_error_rp ( void  ) const
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by AP_AHRS_View::get_error_rp(), DataFlash_Class::Log_Write_Attitude(), and GCS_MAVLINK::send_ahrs().

Here is the caller graph for this function:

◆ get_error_yaw()

virtual float AP_AHRS::get_error_yaw ( void  ) const
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by AP_AHRS_View::get_error_yaw(), DataFlash_Class::Log_Write_Attitude(), and GCS_MAVLINK::send_ahrs().

Here is the caller graph for this function:

◆ get_expected_mag_field_NED()

virtual bool AP_AHRS::get_expected_mag_field_NED ( Vector3f ret) const
inlinevirtual

Definition at line 314 of file AP_AHRS.h.

Referenced by AP_AHRS_View::get_expected_mag_field_NED().

Here is the caller graph for this function:

◆ get_fly_forward()

bool AP_AHRS::get_fly_forward ( void  ) const
inline

Definition at line 97 of file AP_AHRS.h.

Referenced by NavEKF2_core::assume_zero_sideslip(), and NavEKF3_core::assume_zero_sideslip().

Here is the caller graph for this function:

◆ get_gyro()

virtual const Vector3f& AP_AHRS::get_gyro ( void  ) const
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), AP_YawController::get_servo_out(), get_yaw_rate_earth(), DataFlash_Class::Log_Write_Rate(), GCS_MAVLINK::send_attitude(), AP_AHRS_View::update(), and AP_Landing_Deepstall::update_steering().

Here is the caller graph for this function:

◆ get_gyro_drift()

virtual const Vector3f& AP_AHRS::get_gyro_drift ( void  ) const
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by get_gyro_latest(), and GCS_MAVLINK::send_ahrs().

Here is the caller graph for this function:

◆ get_gyro_latest()

Vector3f AP_AHRS::get_gyro_latest ( void  ) const

Definition at line 163 of file AP_AHRS.cpp.

Referenced by AP_AHRS_View::get_gyro_latest().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_hagl()

virtual bool AP_AHRS::get_hagl ( float &  height) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 270 of file AP_AHRS.h.

Referenced by GCS_MAVLINK::_set_mode_common().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_hgt_ctrl_limit()

virtual bool AP_AHRS::get_hgt_ctrl_limit ( float &  limit) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 566 of file AP_AHRS.h.

Referenced by AC_Avoid::adjust_velocity_z().

Here is the caller graph for this function:

◆ get_home()

const struct Location& AP_AHRS::get_home ( void  ) const
inline

◆ get_likely_flying()

bool AP_AHRS::get_likely_flying ( void  ) const
inline

Definition at line 118 of file AP_AHRS.h.

◆ get_mag_field_correction()

virtual bool AP_AHRS::get_mag_field_correction ( Vector3f ret) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 319 of file AP_AHRS.h.

◆ get_optflow()

const OpticalFlow* AP_AHRS::get_optflow ( ) const
inline

Definition at line 158 of file AP_AHRS.h.

Here is the call graph for this function:

◆ get_origin()

virtual bool AP_AHRS::get_origin ( Location ret) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 464 of file AP_AHRS.h.

Referenced by Log_Write_Home_And_Origin(), and GCS_MAVLINK::set_ekf_origin().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_position()

virtual bool AP_AHRS::get_position ( struct Location loc) const
pure virtual

◆ get_primary_accel_index()

virtual uint8_t AP_AHRS::get_primary_accel_index ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 183 of file AP_AHRS.h.

Here is the call graph for this function:

◆ get_primary_gyro_index()

virtual uint8_t AP_AHRS::get_primary_gyro_index ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 188 of file AP_AHRS.h.

Referenced by get_gyro_latest().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_relative_position_D_home()

virtual void AP_AHRS::get_relative_position_D_home ( float &  posD) const
pure virtual

◆ get_relative_position_D_origin()

virtual bool AP_AHRS::get_relative_position_D_origin ( float &  posD) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 354 of file AP_AHRS.h.

Referenced by AC_Avoid::adjust_velocity_z(), AP_AHRS_View::get_relative_position_D_origin(), and DataFlash_Class::Log_Write_POS().

Here is the caller graph for this function:

◆ get_relative_position_NE_home()

virtual bool AP_AHRS::get_relative_position_NE_home ( Vector2f vecNE) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 338 of file AP_AHRS.h.

Referenced by AC_Avoid::adjust_velocity_circle_fence(), and AP_AHRS_View::get_relative_position_NE_home().

Here is the caller graph for this function:

◆ get_relative_position_NE_origin()

virtual bool AP_AHRS::get_relative_position_NE_origin ( Vector2f vecNE) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 344 of file AP_AHRS.h.

Referenced by AC_Avoid::adjust_velocity_polygon(), and AP_AHRS_View::get_relative_position_NE_origin().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_relative_position_NED_home()

virtual bool AP_AHRS::get_relative_position_NED_home ( Vector3f vec) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 326 of file AP_AHRS.h.

Referenced by AP_AHRS_View::get_relative_position_NED_home(), and GCS_MAVLINK::send_local_position().

Here is the caller graph for this function:

◆ get_relative_position_NED_origin()

virtual bool AP_AHRS::get_relative_position_NED_origin ( Vector3f vec) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 333 of file AP_AHRS.h.

Referenced by AP_AHRS_View::get_relative_position_NED_origin(), AP_SmartRTL::set_home(), AP_ICEngine::update(), and AP_SmartRTL::update().

Here is the caller graph for this function:

◆ get_rotation_autopilot_body_to_vehicle_body()

const Matrix3f& AP_AHRS::get_rotation_autopilot_body_to_vehicle_body ( void  ) const
inline

Definition at line 263 of file AP_AHRS.h.

Referenced by AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(), AP_AHRS_NavEKF::update_EKF2(), and AP_AHRS_NavEKF::update_SITL().

Here is the caller graph for this function:

◆ get_rotation_body_to_ned()

virtual const Matrix3f& AP_AHRS::get_rotation_body_to_ned ( void  ) const
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by AP_TECS::_update_throttle_with_airspeed(), AP_TECS::_update_throttle_without_airspeed(), get_yaw_rate_earth(), AP_AHRS_View::update(), AP_TECS::update_50hz(), update_AOA_SSA(), and update_trig().

Here is the caller graph for this function:

◆ get_rotation_vehicle_body_to_autopilot_body()

const Matrix3f& AP_AHRS::get_rotation_vehicle_body_to_autopilot_body ( void  ) const
inline

Definition at line 264 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::euler_angles(), NavEKF2_core::getRotationBodyToNED(), and NavEKF3_core::getRotationBodyToNED().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_secondary_attitude()

virtual bool AP_AHRS::get_secondary_attitude ( Vector3f eulers) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 419 of file AP_AHRS.h.

Referenced by DataFlash_Class::Log_Write_AHRS2(), and GCS_MAVLINK::send_ahrs2().

Here is the caller graph for this function:

◆ get_secondary_position()

virtual bool AP_AHRS::get_secondary_position ( struct Location loc) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 429 of file AP_AHRS.h.

Referenced by DataFlash_Class::Log_Write_AHRS2().

Here is the caller graph for this function:

◆ get_secondary_quaternion()

virtual bool AP_AHRS::get_secondary_quaternion ( Quaternion quat) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 424 of file AP_AHRS.h.

Referenced by DataFlash_Class::Log_Write_AHRS2().

Here is the caller graph for this function:

◆ get_singleton()

static AP_AHRS* AP_AHRS::get_singleton ( )
inlinestatic

Definition at line 83 of file AP_AHRS.h.

Referenced by AP::ahrs().

Here is the caller graph for this function:

◆ get_time_flying_ms()

uint32_t AP_AHRS::get_time_flying_ms ( void  ) const
inline

Definition at line 126 of file AP_AHRS.h.

Referenced by NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), and CompassLearn::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_trim()

const Vector3f& AP_AHRS::get_trim ( ) const
inline

Definition at line 385 of file AP_AHRS.h.

Referenced by NavEKF2_core::getEulerAngles(), and NavEKF3_core::getEulerAngles().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_variances()

virtual bool AP_AHRS::get_variances ( float &  velVar,
float &  posVar,
float &  hgtVar,
Vector3f magVar,
float &  tasVar,
Vector2f offset 
) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 524 of file AP_AHRS.h.

Referenced by AP_Frsky_Telem::check_ekf_status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_vehicle_class()

AHRS_VehicleClass AP_AHRS::get_vehicle_class ( void  ) const
inline

Definition at line 133 of file AP_AHRS.h.

Referenced by NavEKF2_core::assume_zero_sideslip(), and NavEKF3_core::assume_zero_sideslip().

Here is the caller graph for this function:

◆ get_velocity_NED()

virtual bool AP_AHRS::get_velocity_NED ( Vector3f vec) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 309 of file AP_AHRS.h.

Referenced by AP_Frsky_Telem::calc_velandyaw(), AP_Avoidance::check_for_threats(), AR_AttitudeControl::get_forward_speed(), AP_AHRS_View::get_velocity_NED(), GCS_MAVLINK::send_global_position_int(), GCS_MAVLINK::send_local_position(), GCS_MAVLINK::send_vfr_hud(), AP_TECS::update_50hz(), and update_AOA_SSA().

Here is the caller graph for this function:

◆ get_yaw_rate_earth()

float AP_AHRS::get_yaw_rate_earth ( void  ) const
inline

Definition at line 206 of file AP_AHRS.h.

Referenced by AR_AttitudeControl::get_lat_accel(), AP_SteerController::get_steering_out_rate(), and AR_AttitudeControl::get_steering_out_rate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getAOA()

float AP_AHRS::getAOA ( void  )

Definition at line 434 of file AP_AHRS.cpp.

Referenced by getCorrectedDeltaVelocityNED(), and DataFlash_Class::Log_Write_AOA_SSA().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCorrectedDeltaVelocityNED()

virtual void AP_AHRS::getCorrectedDeltaVelocityNED ( Vector3f ret,
float &  dt 
) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 537 of file AP_AHRS.h.

Referenced by AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getLastPosDownReset()

virtual uint32_t AP_AHRS::getLastPosDownReset ( float &  posDelta) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 507 of file AP_AHRS.h.

Referenced by AP_AHRS_View::getLastPosDownReset().

Here is the caller graph for this function:

◆ getLastPosNorthEastReset()

virtual uint32_t AP_AHRS::getLastPosNorthEastReset ( Vector2f pos) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 495 of file AP_AHRS.h.

Referenced by AP_AHRS_View::getLastPosNorthEastReset().

Here is the caller graph for this function:

◆ getLastVelNorthEastReset()

virtual uint32_t AP_AHRS::getLastVelNorthEastReset ( Vector2f vel) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 501 of file AP_AHRS.h.

◆ getLastYawResetAngle()

virtual uint32_t AP_AHRS::getLastYawResetAngle ( float &  yawAng) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 489 of file AP_AHRS.h.

◆ getSSA()

float AP_AHRS::getSSA ( void  )

Definition at line 441 of file AP_AHRS.cpp.

Referenced by getCorrectedDeltaVelocityNED(), and DataFlash_Class::Log_Write_AOA_SSA().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ groundspeed()

float AP_AHRS::groundspeed ( void  )
inline

Definition at line 359 of file AP_AHRS.h.

Referenced by AP_Frsky_Telem::calc_velandyaw(), AP_SteerController::get_steering_out_lat_accel(), AP_SteerController::get_steering_out_rate(), AP_AHRS_View::groundspeed(), GCS_MAVLINK::send_vfr_hud(), and AP_Landing::type_slope_setup_landing_glide_slope().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ groundspeed_vector()

Vector2f AP_AHRS::groundspeed_vector ( void  )
virtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 235 of file AP_AHRS.cpp.

Referenced by airspeed_sensor_enabled(), groundspeed(), AP_AHRS_View::groundspeed_vector(), AP_AHRS_NavEKF::groundspeed_vector(), AP_L1_Control::update_heading_hold(), AP_L1_Control::update_loiter(), AP_L1_Control::update_waypoint(), AP_Landing_Deepstall::verify_breakout(), and AP_Landing_Deepstall::verify_land().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ have_ekf_logging()

virtual bool AP_AHRS::have_ekf_logging ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 219 of file AP_AHRS.h.

◆ have_inertial_nav()

virtual bool AP_AHRS::have_inertial_nav ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 470 of file AP_AHRS.h.

Referenced by GCS_MAVLINK::_set_mode_common().

Here is the caller graph for this function:

◆ healthy()

virtual bool AP_AHRS::healthy ( void  ) const
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by get_active_accel_instance(), and AP_Landing_Deepstall::update_steering().

Here is the caller graph for this function:

◆ home_is_locked()

bool AP_AHRS::home_is_locked ( ) const
inline

Definition at line 444 of file AP_AHRS.h.

◆ home_is_set()

bool AP_AHRS::home_is_set ( void  ) const
inline

Definition at line 449 of file AP_AHRS.h.

Referenced by Log_Write_Home_And_Origin().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

virtual void AP_AHRS::init ( void  )
inlinevirtual

Definition at line 88 of file AP_AHRS.h.

Referenced by setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialised()

virtual bool AP_AHRS::initialised ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 483 of file AP_AHRS.h.

◆ lock_home()

void AP_AHRS::lock_home ( )
inline

Definition at line 441 of file AP_AHRS.h.

◆ Log_Write_Home_And_Origin()

void AP_AHRS::Log_Write_Home_And_Origin ( )

Definition at line 462 of file AP_AHRS.cpp.

Referenced by get_origin(), and GCS_MAVLINK::set_ekf_origin().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ prearm_failure_reason()

virtual const char* AP_AHRS::prearm_failure_reason ( void  ) const
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 214 of file AP_AHRS.h.

◆ reset()

virtual void AP_AHRS::reset ( bool  recover_eulers = false)
pure virtual

Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.

Referenced by AP_InertialSensor::simple_accel_cal().

Here is the caller graph for this function:

◆ reset_attitude()

virtual void AP_AHRS::reset_attitude ( const float &  roll,
const float &  pitch,
const float &  yaw 
)
pure virtual

Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.

◆ reset_gyro_drift()

virtual void AP_AHRS::reset_gyro_drift ( void  )
pure virtual

Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.

Referenced by GCS_MAVLINK::calibrate_gyros().

Here is the caller graph for this function:

◆ resetHeightDatum()

virtual bool AP_AHRS::resetHeightDatum ( void  )
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 516 of file AP_AHRS.h.

◆ rotate_body_to_earth2D()

Vector2f AP_AHRS::rotate_body_to_earth2D ( const Vector2f bf) const

Definition at line 455 of file AP_AHRS.cpp.

Referenced by getCorrectedDeltaVelocityNED().

Here is the caller graph for this function:

◆ rotate_earth_to_body2D()

Vector2f AP_AHRS::rotate_earth_to_body2D ( const Vector2f ef_vector) const

Definition at line 448 of file AP_AHRS.cpp.

Referenced by getCorrectedDeltaVelocityNED().

Here is the caller graph for this function:

◆ set_airspeed()

void AP_AHRS::set_airspeed ( AP_Airspeed airspeed)
inline

Definition at line 166 of file AP_AHRS.h.

◆ set_beacon()

void AP_AHRS::set_beacon ( AP_Beacon beacon)
inline

Definition at line 170 of file AP_AHRS.h.

◆ set_compass()

void AP_AHRS::set_compass ( Compass compass)
inline

Definition at line 145 of file AP_AHRS.h.

Referenced by setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_correct_centrifugal()

void AP_AHRS::set_correct_centrifugal ( bool  setting)
inline

Definition at line 375 of file AP_AHRS.h.

◆ set_fly_forward()

void AP_AHRS::set_fly_forward ( bool  b)
inline

Definition at line 93 of file AP_AHRS.h.

◆ set_home()

virtual void AP_AHRS::set_home ( const Location loc)
pure virtual

Implemented in AP_AHRS_DCM.

Referenced by home_is_set().

Here is the caller graph for this function:

◆ set_likely_flying()

void AP_AHRS::set_likely_flying ( bool  b)
inline

Definition at line 106 of file AP_AHRS.h.

Here is the call graph for this function:

◆ set_optflow()

void AP_AHRS::set_optflow ( const OpticalFlow optflow)
inline

Definition at line 154 of file AP_AHRS.h.

◆ set_orientation()

void AP_AHRS::set_orientation ( )

Definition at line 217 of file AP_AHRS.cpp.

Referenced by get_optflow(), init(), and set_compass().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_origin()

virtual bool AP_AHRS::set_origin ( const Location loc)
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 461 of file AP_AHRS.h.

Referenced by GCS_MAVLINK::set_ekf_origin().

Here is the caller graph for this function:

◆ set_trim()

void AP_AHRS::set_trim ( Vector3f  new_trim)
virtual

Definition at line 190 of file AP_AHRS.cpp.

Referenced by GCS_MAVLINK::_handle_command_preflight_calibration(), get_trim(), and AP_InertialSensor::simple_accel_cal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_vehicle_class()

void AP_AHRS::set_vehicle_class ( AHRS_VehicleClass  vclass)
inline

Definition at line 137 of file AP_AHRS.h.

◆ set_wind_estimation()

void AP_AHRS::set_wind_estimation ( bool  b)
inline

Definition at line 141 of file AP_AHRS.h.

◆ sin_pitch()

float AP_AHRS::sin_pitch ( ) const
inline

Definition at line 408 of file AP_AHRS.h.

◆ sin_roll()

float AP_AHRS::sin_roll ( ) const
inline

Definition at line 405 of file AP_AHRS.h.

◆ sin_yaw()

float AP_AHRS::sin_yaw ( ) const
inline

Definition at line 411 of file AP_AHRS.h.

Referenced by AC_Avoid::adjust_velocity_polygon(), and AR_AttitudeControl::get_forward_speed().

Here is the caller graph for this function:

◆ update()

virtual void AP_AHRS::update ( bool  skip_ins_update = false)
pure virtual

Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.

Referenced by get_yaw_rate_earth().

Here is the caller graph for this function:

◆ update_AOA_SSA()

void AP_AHRS::update_AOA_SSA ( void  )
virtual

Definition at line 387 of file AP_AHRS.cpp.

Referenced by getAOA(), getCorrectedDeltaVelocityNED(), getSSA(), and AP_AHRS_DCM::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_cd_values()

void AP_AHRS::update_cd_values ( void  )
protected

Definition at line 352 of file AP_AHRS.cpp.

Referenced by AP_AHRS_DCM::euler_angles(), AP_AHRS_NavEKF::update_DCM(), AP_AHRS_NavEKF::update_EKF2(), AP_AHRS_NavEKF::update_EKF3(), and AP_AHRS_NavEKF::update_SITL().

Here is the caller graph for this function:

◆ update_trig()

void AP_AHRS::update_trig ( void  )
protected

Definition at line 336 of file AP_AHRS.cpp.

Referenced by AP_AHRS_DCM::update(), AP_AHRS_NavEKF::update_EKF2(), AP_AHRS_NavEKF::update_EKF3(), and AP_AHRS_NavEKF::update_SITL().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ uptime_ms()

virtual uint32_t AP_AHRS::uptime_ms ( void  ) const
pure virtual

Implemented in AP_AHRS_DCM.

Referenced by get_variances().

Here is the caller graph for this function:

◆ use_compass()

virtual bool AP_AHRS::use_compass ( void  )
inlinevirtual

Reimplemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.

Definition at line 364 of file AP_AHRS.h.

Here is the call graph for this function:

◆ wind_estimate()

virtual Vector3f AP_AHRS::wind_estimate ( void  ) const
pure virtual

Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.

Referenced by AP_Landing_Deepstall::build_approach_path(), get_hagl(), groundspeed_vector(), AP_Landing::head_wind(), update_AOA_SSA(), SoaringController::update_thermalling(), AP_Landing_Deepstall::verify_land(), AP_Landing::wind_alignment(), and AP_AHRS_View::wind_estimate().

Here is the caller graph for this function:

◆ writeExtNavData()

virtual void AP_AHRS::writeExtNavData ( const Vector3f sensOffset,
const Vector3f pos,
const Quaternion quat,
float  posErr,
float  angErr,
uint32_t  timeStamp_ms,
uint32_t  resetTime_ms 
)
inlinevirtual

Reimplemented in AP_AHRS_NavEKF.

Definition at line 569 of file AP_AHRS.h.

Referenced by GCS_MAVLINK::handle_att_pos_mocap(), and GCS_MAVLINK::handle_common_vision_position_estimate_data().

Here is the caller graph for this function:

◆ yaw_initialised()

bool AP_AHRS::yaw_initialised ( void  ) const
inline

Definition at line 369 of file AP_AHRS.h.

Friends And Related Function Documentation

◆ AP_AHRS_View

friend class AP_AHRS_View
friend

Definition at line 53 of file AP_AHRS.h.

Referenced by create_view().

Member Data Documentation

◆ _accel_ef

Vector3f AP_AHRS::_accel_ef[INS_MAX_INSTANCES]
protected

Definition at line 645 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::_yaw_gain(), AP_AHRS_DCM::drift_correction(), and get_accel_ef().

◆ _accel_ef_blended

Vector3f AP_AHRS::_accel_ef_blended
protected

Definition at line 646 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::drift_correction(), and get_accel_ef_blended().

◆ _active_accel_instance

uint8_t AP_AHRS::_active_accel_instance
protected

◆ _airspeed

AP_Airspeed* AP_AHRS::_airspeed
protected

◆ _AOA

float AP_AHRS::_AOA
protected

Definition at line 670 of file AP_AHRS.h.

Referenced by getAOA(), and update_AOA_SSA().

◆ _beacon

AP_Beacon* AP_AHRS::_beacon
protected

Definition at line 627 of file AP_AHRS.h.

Referenced by get_beacon(), and set_beacon().

◆ _board_orientation

AP_Int8 AP_AHRS::_board_orientation
protected

Definition at line 583 of file AP_AHRS.h.

Referenced by set_orientation().

◆ _compass

Compass* AP_AHRS::_compass
protected

◆ _compass_last_update

uint32_t AP_AHRS::_compass_last_update
protected

Definition at line 630 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::drift_correction_yaw().

◆ _cos_pitch

float AP_AHRS::_cos_pitch
protected

Definition at line 660 of file AP_AHRS.h.

Referenced by cos_pitch(), and update_trig().

◆ _cos_roll

float AP_AHRS::_cos_roll
protected

Definition at line 660 of file AP_AHRS.h.

Referenced by cos_roll(), and update_trig().

◆ _cos_yaw

float AP_AHRS::_cos_yaw
protected

Definition at line 660 of file AP_AHRS.h.

Referenced by cos_yaw(), rotate_body_to_earth2D(), rotate_earth_to_body2D(), and update_trig().

◆ _custom_pitch

AP_Float AP_AHRS::_custom_pitch
protected

Definition at line 588 of file AP_AHRS.h.

Referenced by set_orientation().

◆ _custom_roll

AP_Float AP_AHRS::_custom_roll
protected

Definition at line 587 of file AP_AHRS.h.

Referenced by set_orientation().

◆ _custom_rotation

Matrix3f AP_AHRS::_custom_rotation
protected

Definition at line 591 of file AP_AHRS.h.

Referenced by set_orientation().

◆ _custom_yaw

AP_Float AP_AHRS::_custom_yaw
protected

Definition at line 589 of file AP_AHRS.h.

Referenced by set_orientation().

◆ _ekf_type

AP_Int8 AP_AHRS::_ekf_type
protected

◆ _flags

struct AP_AHRS::ahrs_flags AP_AHRS::_flags
protected

◆ _gps_delay

AP_Int8 AP_AHRS::_gps_delay
protected

Definition at line 585 of file AP_AHRS.h.

◆ _gps_minsats

AP_Int8 AP_AHRS::_gps_minsats
protected

Definition at line 584 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::drift_correction().

◆ _gps_use

AP_Int8 AP_AHRS::_gps_use
protected

Definition at line 581 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::have_gps().

◆ _gyro_drift_limit

float AP_AHRS::_gyro_drift_limit
protected

Definition at line 642 of file AP_AHRS.h.

Referenced by AP_AHRS(), and AP_AHRS_DCM::drift_correction().

◆ _home

struct Location AP_AHRS::_home
protected

◆ _home_is_set

bool AP_AHRS::_home_is_set
protected

Definition at line 656 of file AP_AHRS.h.

Referenced by home_is_set(), and AP_AHRS_DCM::set_home().

◆ _home_locked

bool AP_AHRS::_home_locked
protected

Definition at line 657 of file AP_AHRS.h.

Referenced by home_is_locked(), and lock_home().

◆ _hp

Vector2f AP_AHRS::_hp
protected

Definition at line 651 of file AP_AHRS.h.

Referenced by groundspeed_vector().

◆ _kp

AP_Float AP_AHRS::_kp
protected

Definition at line 577 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::drift_correction().

◆ _kp_yaw

AP_Float AP_AHRS::_kp_yaw
protected

Definition at line 576 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::drift_correction_yaw().

◆ _last_AOA_update_ms

uint32_t AP_AHRS::_last_AOA_update_ms
protected

Definition at line 671 of file AP_AHRS.h.

Referenced by update_AOA_SSA().

◆ _last_flying_ms

uint32_t AP_AHRS::_last_flying_ms
protected

Definition at line 603 of file AP_AHRS.h.

Referenced by get_time_flying_ms(), and set_likely_flying().

◆ _last_trim

Vector3f AP_AHRS::_last_trim
protected

Definition at line 636 of file AP_AHRS.h.

Referenced by AP_AHRS(), and update_trig().

◆ _lastGndVelADS

Vector2f AP_AHRS::_lastGndVelADS
protected

Definition at line 652 of file AP_AHRS.h.

Referenced by groundspeed_vector().

◆ _lp

Vector2f AP_AHRS::_lp
protected

Definition at line 650 of file AP_AHRS.h.

Referenced by groundspeed_vector().

◆ _optflow

const OpticalFlow* AP_AHRS::_optflow
protected

Definition at line 621 of file AP_AHRS.h.

Referenced by get_optflow(), and set_optflow().

◆ _rotation_autopilot_body_to_vehicle_body

Matrix3f AP_AHRS::_rotation_autopilot_body_to_vehicle_body
protected

Definition at line 637 of file AP_AHRS.h.

Referenced by AP_AHRS(), get_rotation_autopilot_body_to_vehicle_body(), and update_trig().

◆ _rotation_vehicle_body_to_autopilot_body

Matrix3f AP_AHRS::_rotation_vehicle_body_to_autopilot_body
protected

Definition at line 638 of file AP_AHRS.h.

Referenced by AP_AHRS(), get_rotation_vehicle_body_to_autopilot_body(), and update_trig().

◆ _sin_pitch

float AP_AHRS::_sin_pitch
protected

Definition at line 661 of file AP_AHRS.h.

Referenced by sin_pitch(), and update_trig().

◆ _sin_roll

float AP_AHRS::_sin_roll
protected

Definition at line 661 of file AP_AHRS.h.

Referenced by sin_roll(), and update_trig().

◆ _sin_yaw

float AP_AHRS::_sin_yaw
protected

Definition at line 661 of file AP_AHRS.h.

Referenced by rotate_body_to_earth2D(), rotate_earth_to_body2D(), sin_yaw(), and update_trig().

◆ _singleton

AP_AHRS * AP_AHRS::_singleton
staticprivate

Definition at line 674 of file AP_AHRS.h.

Referenced by AP_AHRS(), get_singleton(), and Log_Write_Home_And_Origin().

◆ _SSA

float AP_AHRS::_SSA
protected

Definition at line 670 of file AP_AHRS.h.

Referenced by getSSA(), and update_AOA_SSA().

◆ _trim

AP_Vector3f AP_AHRS::_trim
protected

Definition at line 633 of file AP_AHRS.h.

Referenced by add_trim(), AP_AHRS(), get_trim(), set_trim(), and update_trig().

◆ _vehicle_class

AHRS_VehicleClass AP_AHRS::_vehicle_class
protected

◆ _view

AP_AHRS_View* AP_AHRS::_view
protected

Definition at line 667 of file AP_AHRS.h.

Referenced by create_view(), and AP_AHRS_NavEKF::update().

◆ _wind_max

AP_Int8 AP_AHRS::_wind_max
protected

Definition at line 582 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::airspeed_estimate(), and airspeed_estimate().

◆ beta

AP_Float AP_AHRS::beta
protected

Definition at line 580 of file AP_AHRS.h.

Referenced by groundspeed_vector().

◆ gps_gain

AP_Float AP_AHRS::gps_gain
protected

Definition at line 578 of file AP_AHRS.h.

Referenced by AP_AHRS_DCM::drift_correction().

◆ pitch

float AP_AHRS::pitch

◆ pitch_sensor

int32_t AP_AHRS::pitch_sensor

◆ roll

float AP_AHRS::roll

◆ roll_sensor

int32_t AP_AHRS::roll_sensor

◆ var_info

const AP_Param::GroupInfo AP_AHRS::var_info
static

Definition at line 416 of file AP_AHRS.h.

Referenced by AP_AHRS().

◆ yaw

float AP_AHRS::yaw

◆ yaw_sensor

int32_t AP_AHRS::yaw_sensor

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