ArduCopter: rename for AHRS restructuring

This commit is contained in:
Peter Barker 2021-07-20 22:16:33 +10:00 committed by Peter Barker
parent d74bb146f1
commit e74a8e28af
3 changed files with 6 additions and 6 deletions

View File

@ -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();

View File

@ -50,7 +50,7 @@
#include <Filter/Filter.h> // Filter library
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
#include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
#include <AP_InertialNav/AP_InertialNav_NavEKF.h> // ArduPilot Mega inertial navigation library
#include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
#include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
#include <AC_WPNav/AC_Circle.h> // circle navigation library

View File

@ -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();