diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index dc3e3a21d2..06889471ff 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -244,7 +244,7 @@ bool AP_Arming_Blimp::pre_arm_ekf_attitude_check() bool AP_Arming_Blimp::mandatory_gps_checks(bool display_failure) { // always check if inertial nav has started and is ready - const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); + const auto &ahrs = AP::ahrs(); char failure_msg[50] = {}; if (!ahrs.pre_arm_check(false, failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "AHRS: %s", failure_msg); @@ -363,7 +363,7 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c gcs().send_text(MAV_SEVERITY_INFO, "Arming motors"); //MIR kept in - usually only in SITL - AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); + auto &ahrs = AP::ahrs(); blimp.initial_armed_bearing = ahrs.yaw_sensor; @@ -425,7 +425,7 @@ bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_chec gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors"); //MIR keeping in - usually only in SITL - AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); + auto &ahrs = AP::ahrs(); // save compass offsets learned by the EKF if enabled Compass &compass = AP::compass(); diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 04d39599c3..f8ca967bd8 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -44,7 +44,7 @@ #include // Filter library #include // needed for AHRS build #include // needed for AHRS build -#include // ArduPilot Mega inertial navigation library +#include // ArduPilot Mega inertial navigation library #include // RC input mapping library #include // Battery monitor library #include diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index dc5915e7a8..e107898cfb 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -98,7 +98,7 @@ void Blimp::Log_Write_Attitude() // Write an EKF and POS packet void Blimp::Log_Write_EKF_POS() { - AP::ahrs_navekf().Log_Write(); + AP::ahrs().Log_Write(); ahrs.Write_AHRS2(); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE();