From e74a8e28af7867aaed736e18689c96e376519a2b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 20 Jul 2021 22:16:33 +1000 Subject: [PATCH] ArduCopter: rename for AHRS restructuring --- ArduCopter/AP_Arming.cpp | 8 ++++---- ArduCopter/Copter.h | 2 +- ArduCopter/Log.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index b1632e1c1d..fda9ab04f7 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -512,7 +512,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) bool mode_requires_gps = copter.flightmode->requires_GPS(); // 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(mode_requires_gps, failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "AHRS: %s", failure_msg); @@ -638,7 +638,7 @@ bool AP_Arming_Copter::alt_checks(bool display_failure) // has side-effect that logging is started bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) { - const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); + const auto &ahrs = AP::ahrs(); // always check if inertial nav has started and is ready if (!ahrs.healthy()) { @@ -815,7 +815,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ // -------------------- copter.init_simple_bearing(); - AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); + auto &ahrs = AP::ahrs(); copter.initial_armed_bearing = ahrs.yaw_sensor; @@ -905,7 +905,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors"); #endif - 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/ArduCopter/Copter.h b/ArduCopter/Copter.h index 6fbfe4605c..96c2764fe0 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -50,7 +50,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 // ArduCopter waypoint navigation library #include // ArduCopter Loiter Mode Library #include // circle navigation library diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index a790138c9f..1352fe0b49 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -86,7 +86,7 @@ void Copter::Log_Write_Attitude() // Write an EKF and POS packet void Copter::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();