APM:Libraries
|
#include <AP_AHRS.h>
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 Compass * | get_compass () const |
void | set_optflow (const OpticalFlow *optflow) |
const OpticalFlow * | get_optflow () const |
void | set_orientation () |
void | set_airspeed (AP_Airspeed *airspeed) |
void | set_beacon (AP_Beacon *beacon) |
const AP_Airspeed * | get_airspeed (void) const |
const AP_Beacon * | get_beacon (void) const |
virtual uint8_t | get_primary_accel_index (void) const |
virtual uint8_t | get_primary_gyro_index (void) const |
virtual const Vector3f & | get_accel_ef (uint8_t i) const |
virtual const Vector3f & | get_accel_ef (void) const |
virtual const Vector3f & | get_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 Vector3f & | get_gyro (void) const =0 |
Vector3f | get_gyro_latest (void) const |
virtual const Vector3f & | get_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 Matrix3f & | get_rotation_body_to_ned (void) const =0 |
const Matrix3f & | get_rotation_autopilot_body_to_vehicle_body (void) const |
const Matrix3f & | get_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 Vector3f & | get_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 Location & | get_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_View * | create_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_AHRS * | get_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) |
Static Private Attributes | |
static AP_AHRS * | _singleton |
Friends | |
class | AP_AHRS_View |
|
inline |
|
virtual |
Definition at line 199 of file AP_AHRS.cpp.
Referenced by get_trim().
|
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().
|
inline |
Definition at line 281 of file AP_AHRS.h.
Referenced by AP_AHRS_View::airspeed_estimate_true(), and groundspeed_vector().
|
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().
|
protected |
Definition at line 290 of file AP_AHRS.cpp.
Referenced by AP_AHRS_View::update(), and update_trig().
|
inline |
Definition at line 402 of file AP_AHRS.h.
Referenced by AC_Avoid::adjust_velocity_polygon(), and AR_AttitudeControl::get_forward_speed().
AP_AHRS_View * AP_AHRS::create_view | ( | enum Rotation | rotation | ) |
Definition at line 364 of file AP_AHRS.cpp.
Referenced by getCorrectedDeltaVelocityNED().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 193 of file AP_AHRS.h.
Referenced by AP_TECS::update_50hz().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 196 of file AP_AHRS.h.
Referenced by AP_AHRS_NavEKF::get_accel_ef().
|
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().
|
inline |
|
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().
|
inline |
Definition at line 178 of file AP_AHRS.h.
Referenced by DataFlash_Class::Log_Write_POS(), NavEKF2_core::readRngBcnData(), and NavEKF3_core::readRngBcnData().
|
inline |
Definition at line 150 of file AP_AHRS.h.
Referenced by NavEKF2_core::alignMagStateDeclination(), NavEKF3_core::alignMagStateDeclination(), SoloGimbalEKF::calcMagHeadingInnov(), NavEKF2_core::calcQuatAndFieldStates(), NavEKF3_core::calcQuatAndFieldStates(), NavEKF3::check_log_write(), NavEKF2::check_log_write(), NavEKF2_core::FuseDeclination(), NavEKF3_core::FuseDeclination(), NavEKF2_core::fuseEulerYaw(), NavEKF3_core::fuseEulerYaw(), NavEKF2_core::getMagOffsets(), NavEKF3_core::getMagOffsets(), NavEKF2_core::InitialiseVariables(), NavEKF3_core::InitialiseVariables(), SoloGimbalEKF::readMagData(), NavEKF2_core::readMagData(), NavEKF3_core::readMagData(), NavEKF2_core::use_compass(), and NavEKF3_core::use_compass().
|
inline |
|
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().
|
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().
|
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().
|
inlinevirtual |
Definition at line 314 of file AP_AHRS.h.
Referenced by AP_AHRS_View::get_expected_mag_field_NED().
|
inline |
Definition at line 97 of file AP_AHRS.h.
Referenced by NavEKF2_core::assume_zero_sideslip(), and NavEKF3_core::assume_zero_sideslip().
|
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().
|
pure virtual |
Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.
Referenced by get_gyro_latest(), and GCS_MAVLINK::send_ahrs().
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().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 270 of file AP_AHRS.h.
Referenced by GCS_MAVLINK::_set_mode_common().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 566 of file AP_AHRS.h.
Referenced by AC_Avoid::adjust_velocity_z().
|
inline |
Definition at line 435 of file AP_AHRS.h.
Referenced by AP_Rally::calc_best_rally_or_home_location(), AP_Frsky_Telem::calc_home(), AP_Frsky_Telem::calc_nav_alt(), AC_Fence::check_destination_within_fence(), AP_Rally::find_nearest_rally_point(), Location_Class::get_alt_cm(), AP_AHRS_NavEKF::get_hagl(), AP_AHRS_NavEKF::get_relative_position_D_origin(), AP_AHRS_NavEKF::get_relative_position_NE_origin(), AP_AHRS_NavEKF::get_relative_position_NED_origin(), NavEKF2_core::InitialiseFilterBootstrap(), NavEKF3_core::InitialiseFilterBootstrap(), DataFlash_Class::Log_Write_CameraInfo(), AP_Rally::rally_location_to_location(), AP_Mission::read_cmd_from_storage(), AP_Camera::send_feedback(), GCS_MAVLINK::send_home(), NavEKF2_core::setOrigin(), NavEKF3_core::setOrigin(), NavEKF2_core::setOriginLLH(), NavEKF3_core::setOriginLLH(), and AP_Mission::write_home_to_storage().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
|
inline |
|
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().
|
pure virtual |
Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.
Referenced by AP_Frsky_Telem::calc_home(), AP_Frsky_Telem::calc_nav_alt(), AP_Avoidance::check_for_threats(), AP_Mission::get_landing_sequence_start(), AP_AHRS_View::get_position(), get_rotation_vehicle_body_to_autopilot_body(), AP_Avoidance::get_vector_perpendicular(), AP_Arming::gps_checks(), AP_Avoidance::handle_avoidance_local(), SoaringController::init_thermalling(), DataFlash_Class::Log_Write_POS(), AP_DEVO_Telem::send_frames(), GCS_MAVLINK::send_global_position_int(), GCS_MAVLINK::send_vfr_hud(), AP_Landing_Deepstall::terminate(), CompassLearn::update(), AP_L1_Control::update_loiter(), AP_Landing_Deepstall::update_steering(), SoaringController::update_thermalling(), AP_L1_Control::update_waypoint(), and AP_Landing_Deepstall::verify_land().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 183 of file AP_AHRS.h.
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 188 of file AP_AHRS.h.
Referenced by get_gyro_latest().
|
pure virtual |
Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.
Referenced by AC_Avoid::adjust_velocity_z(), SoaringController::get_altitude_wrt_home(), AP_AHRS_View::get_relative_position_D_home(), get_relative_position_NE_origin(), GCS_MAVLINK::global_position_int_relative_alt(), DataFlash_Class::Log_Write_POS(), AP_Landing_Deepstall::request_go_around(), AP_DEVO_Telem::send_frames(), GCS_MAVLINK::send_vfr_hud(), Variometer::update(), AP_TECS::update_50hz(), and AP_Landing_Deepstall::verify_land().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
inline |
Definition at line 264 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::euler_angles(), NavEKF2_core::getRotationBodyToNED(), and NavEKF3_core::getRotationBodyToNED().
|
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().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 429 of file AP_AHRS.h.
Referenced by DataFlash_Class::Log_Write_AHRS2().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 424 of file AP_AHRS.h.
Referenced by DataFlash_Class::Log_Write_AHRS2().
|
inlinestatic |
Definition at line 83 of file AP_AHRS.h.
Referenced by AP::ahrs().
|
inline |
Definition at line 126 of file AP_AHRS.h.
Referenced by NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), and CompassLearn::update().
|
inline |
Definition at line 385 of file AP_AHRS.h.
Referenced by NavEKF2_core::getEulerAngles(), and NavEKF3_core::getEulerAngles().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 524 of file AP_AHRS.h.
Referenced by AP_Frsky_Telem::check_ekf_status().
|
inline |
Definition at line 133 of file AP_AHRS.h.
Referenced by NavEKF2_core::assume_zero_sideslip(), and NavEKF3_core::assume_zero_sideslip().
|
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().
|
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().
float AP_AHRS::getAOA | ( | void | ) |
Definition at line 434 of file AP_AHRS.cpp.
Referenced by getCorrectedDeltaVelocityNED(), and DataFlash_Class::Log_Write_AOA_SSA().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 537 of file AP_AHRS.h.
Referenced by AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 507 of file AP_AHRS.h.
Referenced by AP_AHRS_View::getLastPosDownReset().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 495 of file AP_AHRS.h.
Referenced by AP_AHRS_View::getLastPosNorthEastReset().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
float AP_AHRS::getSSA | ( | void | ) |
Definition at line 441 of file AP_AHRS.cpp.
Referenced by getCorrectedDeltaVelocityNED(), and DataFlash_Class::Log_Write_AOA_SSA().
|
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().
|
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().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 470 of file AP_AHRS.h.
Referenced by GCS_MAVLINK::_set_mode_common().
|
pure virtual |
Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.
Referenced by get_active_accel_instance(), and AP_Landing_Deepstall::update_steering().
|
inline |
Definition at line 449 of file AP_AHRS.h.
Referenced by Log_Write_Home_And_Origin().
|
inlinevirtual |
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
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().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
|
pure virtual |
Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.
Referenced by AP_InertialSensor::simple_accel_cal().
|
pure virtual |
Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.
|
pure virtual |
Implemented in AP_AHRS_NavEKF, and AP_AHRS_DCM.
Referenced by GCS_MAVLINK::calibrate_gyros().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 455 of file AP_AHRS.cpp.
Referenced by getCorrectedDeltaVelocityNED().
Definition at line 448 of file AP_AHRS.cpp.
Referenced by getCorrectedDeltaVelocityNED().
|
inline |
|
inline |
|
inline |
|
pure virtual |
Implemented in AP_AHRS_DCM.
Referenced by home_is_set().
|
inline |
|
inline |
void AP_AHRS::set_orientation | ( | ) |
Definition at line 217 of file AP_AHRS.cpp.
Referenced by get_optflow(), init(), and set_compass().
|
inlinevirtual |
Reimplemented in AP_AHRS_NavEKF.
Definition at line 461 of file AP_AHRS.h.
Referenced by GCS_MAVLINK::set_ekf_origin().
|
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().
|
inline |
|
inline |
Definition at line 411 of file AP_AHRS.h.
Referenced by AC_Avoid::adjust_velocity_polygon(), and AR_AttitudeControl::get_forward_speed().
|
pure virtual |
Implemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.
Referenced by get_yaw_rate_earth().
|
virtual |
Definition at line 387 of file AP_AHRS.cpp.
Referenced by getAOA(), getCorrectedDeltaVelocityNED(), getSSA(), and AP_AHRS_DCM::update().
|
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().
|
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().
|
pure virtual |
Implemented in AP_AHRS_DCM.
Referenced by get_variances().
|
inlinevirtual |
Reimplemented in AP_AHRS_DCM, and AP_AHRS_NavEKF.
Definition at line 364 of file AP_AHRS.h.
|
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().
|
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().
|
friend |
Definition at line 53 of file AP_AHRS.h.
Referenced by create_view().
|
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().
|
protected |
Definition at line 646 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction(), and get_accel_ef_blended().
|
protected |
Definition at line 664 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::_yaw_gain(), AP_AHRS_DCM::drift_correction(), and get_active_accel_instance().
|
protected |
Definition at line 624 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::airspeed_estimate(), airspeed_estimate(), airspeed_sensor_enabled(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::estimate_wind(), get_airspeed(), get_EAS2TAS(), and set_airspeed().
|
protected |
Definition at line 670 of file AP_AHRS.h.
Referenced by getAOA(), and update_AOA_SSA().
|
protected |
Definition at line 627 of file AP_AHRS.h.
Referenced by get_beacon(), and set_beacon().
|
protected |
Definition at line 583 of file AP_AHRS.h.
Referenced by set_orientation().
|
protected |
Definition at line 618 of file AP_AHRS.h.
Referenced by AP_AHRS_NavEKF::active_EKF_type(), AP_AHRS_DCM::drift_correction_yaw(), get_compass(), set_compass(), set_orientation(), AP_AHRS_DCM::use_compass(), use_compass(), and AP_AHRS_DCM::yaw_error_compass().
|
protected |
Definition at line 630 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction_yaw().
|
protected |
Definition at line 660 of file AP_AHRS.h.
Referenced by cos_pitch(), and update_trig().
|
protected |
Definition at line 660 of file AP_AHRS.h.
Referenced by cos_roll(), and update_trig().
|
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().
|
protected |
Definition at line 588 of file AP_AHRS.h.
Referenced by set_orientation().
|
protected |
Definition at line 587 of file AP_AHRS.h.
Referenced by set_orientation().
|
protected |
Definition at line 591 of file AP_AHRS.h.
Referenced by set_orientation().
|
protected |
Definition at line 589 of file AP_AHRS.h.
Referenced by set_orientation().
|
protected |
Definition at line 586 of file AP_AHRS.h.
Referenced by AP_AHRS_NavEKF::ekf_type(), get_ekf_type(), AP_AHRS_NavEKF::set_ekf_use(), and AP_AHRS_NavEKF::update().
|
protected |
Referenced by AP_AHRS_NavEKF::active_EKF_type(), AP_AHRS_DCM::airspeed_estimate(), AP_AHRS(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::drift_correction_yaw(), AP_AHRS_DCM::estimate_wind(), get_correct_centrifugal(), get_fly_forward(), get_likely_flying(), AP_AHRS_DCM::get_position(), get_time_flying_ms(), set_correct_centrifugal(), set_fly_forward(), set_likely_flying(), set_wind_estimation(), AP_AHRS_DCM::use_compass(), and yaw_initialised().
|
protected |
Definition at line 584 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction().
|
protected |
Definition at line 581 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::have_gps().
|
protected |
Definition at line 642 of file AP_AHRS.h.
Referenced by AP_AHRS(), and AP_AHRS_DCM::drift_correction().
|
protected |
Definition at line 655 of file AP_AHRS.h.
Referenced by get_home(), AP_AHRS_DCM::get_position(), AP_AHRS_NavEKF::get_relative_position_D_home(), AP_AHRS_NavEKF::get_relative_position_NE_home(), AP_AHRS_NavEKF::get_relative_position_NED_home(), Log_Write_Home_And_Origin(), and AP_AHRS_DCM::set_home().
|
protected |
Definition at line 656 of file AP_AHRS.h.
Referenced by home_is_set(), and AP_AHRS_DCM::set_home().
|
protected |
Definition at line 657 of file AP_AHRS.h.
Referenced by home_is_locked(), and lock_home().
|
protected |
Definition at line 651 of file AP_AHRS.h.
Referenced by groundspeed_vector().
|
protected |
Definition at line 577 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction().
|
protected |
Definition at line 576 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction_yaw().
|
protected |
Definition at line 671 of file AP_AHRS.h.
Referenced by update_AOA_SSA().
|
protected |
Definition at line 603 of file AP_AHRS.h.
Referenced by get_time_flying_ms(), and set_likely_flying().
|
protected |
Definition at line 636 of file AP_AHRS.h.
Referenced by AP_AHRS(), and update_trig().
|
protected |
Definition at line 652 of file AP_AHRS.h.
Referenced by groundspeed_vector().
|
protected |
Definition at line 650 of file AP_AHRS.h.
Referenced by groundspeed_vector().
|
protected |
Definition at line 621 of file AP_AHRS.h.
Referenced by get_optflow(), and set_optflow().
|
protected |
Definition at line 637 of file AP_AHRS.h.
Referenced by AP_AHRS(), get_rotation_autopilot_body_to_vehicle_body(), and update_trig().
|
protected |
Definition at line 638 of file AP_AHRS.h.
Referenced by AP_AHRS(), get_rotation_vehicle_body_to_autopilot_body(), and update_trig().
|
protected |
Definition at line 661 of file AP_AHRS.h.
Referenced by sin_pitch(), and update_trig().
|
protected |
Definition at line 661 of file AP_AHRS.h.
Referenced by sin_roll(), and update_trig().
|
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().
|
staticprivate |
Definition at line 674 of file AP_AHRS.h.
Referenced by AP_AHRS(), get_singleton(), and Log_Write_Home_And_Origin().
|
protected |
Definition at line 670 of file AP_AHRS.h.
Referenced by getSSA(), and update_AOA_SSA().
|
protected |
Definition at line 633 of file AP_AHRS.h.
Referenced by add_trim(), AP_AHRS(), get_trim(), set_trim(), and update_trig().
|
protected |
Definition at line 572 of file AP_AHRS.h.
Referenced by AP_AHRS_NavEKF::active_EKF_type(), get_vehicle_class(), AP_AHRS_NavEKF::healthy(), and set_vehicle_class().
|
protected |
Definition at line 667 of file AP_AHRS.h.
Referenced by create_view(), and AP_AHRS_NavEKF::update().
|
protected |
Definition at line 582 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::airspeed_estimate(), and airspeed_estimate().
|
protected |
Definition at line 580 of file AP_AHRS.h.
Referenced by groundspeed_vector().
|
protected |
Definition at line 578 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction().
float AP_AHRS::pitch |
Definition at line 225 of file AP_AHRS.h.
Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_TECS::_initialise_states(), AP_AHRS_DCM::drift_correction_yaw(), AP_AHRS_DCM::euler_angles(), AP_AHRS_DCM::get_gyro_drift(), loop(), AP_L1_Control::nav_roll_cd(), AP_AHRS_NavEKF::reset(), AP_AHRS_DCM::reset(), AP_AHRS_NavEKF::reset_attitude(), GCS_MAVLINK::send_attitude(), CompassLearn::update(), update_cd_values(), AP_AHRS_NavEKF::update_DCM(), AP_AHRS_NavEKF::update_EKF2(), AP_AHRS_NavEKF::update_EKF3(), and AP_AHRS_NavEKF::update_SITL().
int32_t AP_AHRS::pitch_sensor |
Definition at line 230 of file AP_AHRS.h.
Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_PitchController::_get_rate_out(), AP_Frsky_Telem::calc_attiandrng(), AP_AHRS_DCM::drift_correction(), DataFlash_Class::Log_Write_Attitude(), DataFlash_Class::Log_Write_CameraInfo(), AP_Camera::send_feedback(), and update_cd_values().
float AP_AHRS::roll |
Definition at line 224 of file AP_AHRS.h.
Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::drift_correction_yaw(), AP_AHRS_DCM::euler_angles(), AP_AHRS_DCM::get_gyro_drift(), AP_YawController::get_servo_out(), loop(), AP_AHRS_NavEKF::reset(), AP_AHRS_DCM::reset(), AP_AHRS_NavEKF::reset_attitude(), GCS_MAVLINK::send_attitude(), CompassLearn::update(), Variometer::update(), update_cd_values(), AP_AHRS_NavEKF::update_DCM(), AP_AHRS_NavEKF::update_EKF2(), AP_AHRS_NavEKF::update_EKF3(), and AP_AHRS_NavEKF::update_SITL().
int32_t AP_AHRS::roll_sensor |
Definition at line 229 of file AP_AHRS.h.
Referenced by AP_PitchController::_get_rate_out(), AP_Frsky_Telem::calc_attiandrng(), DataFlash_Class::Log_Write_Attitude(), DataFlash_Class::Log_Write_CameraInfo(), AP_Camera::send_feedback(), AP_Camera::update(), and update_cd_values().
|
static |
float AP_AHRS::yaw |
Definition at line 226 of file AP_AHRS.h.
Referenced by AP_AHRS_DCM::drift_correction_yaw(), AP_AHRS_DCM::euler_angles(), AP_AHRS_DCM::get_gyro_drift(), AR_AttitudeControl::get_steering_out_heading(), AP_L1_Control::get_yaw(), groundspeed_vector(), SoaringController::init_thermalling(), loop(), AP_AHRS_NavEKF::reset(), AP_AHRS_DCM::reset(), AP_AHRS_NavEKF::reset_attitude(), GCS_MAVLINK::send_attitude(), CompassLearn::update(), update_cd_values(), AP_AHRS_NavEKF::update_DCM(), AP_AHRS_NavEKF::update_EKF2(), AP_AHRS_NavEKF::update_EKF3(), AP_L1_Control::update_level_flight(), AP_L1_Control::update_loiter(), AP_AHRS_NavEKF::update_SITL(), and AP_Landing_Deepstall::update_steering().
int32_t AP_AHRS::yaw_sensor |
Definition at line 231 of file AP_AHRS.h.
Referenced by AP_Landing_Deepstall::build_approach_path(), AP_Frsky_Telem::calc_velandyaw(), AR_AttitudeControl::get_forward_speed(), AP_L1_Control::get_yaw_sensor(), AP_Landing::head_wind(), DataFlash_Class::Log_Write_Attitude(), DataFlash_Class::Log_Write_CameraInfo(), AP_Frsky_Telem::send_D(), AP_Camera::send_feedback(), GCS_MAVLINK::send_global_position_int(), AP_Frsky_Telem::send_SPort(), GCS_MAVLINK::send_vfr_hud(), update_cd_values(), AP_L1_Control::update_heading_hold(), AP_L1_Control::update_level_flight(), and AP_AHRS_DCM::use_compass().