ArduPlane: rename for AHRS restructuring

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

View File

@ -35,7 +35,7 @@ void Plane::Log_Write_Attitude(void)
logger.Write_PID(LOG_PIDY_MSG, yawController.get_pid_info()); logger.Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
logger.Write_PID(LOG_PIDS_MSG, steerController.get_pid_info()); logger.Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
AP::ahrs_navekf().Log_Write(); AP::ahrs().Log_Write();
ahrs.Write_AHRS2(); ahrs.Write_AHRS2();
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL

View File

@ -632,7 +632,7 @@ const AP_Param::ConversionInfo q_conversion_table[] = {
}; };
QuadPlane::QuadPlane(AP_AHRS_NavEKF &_ahrs) : QuadPlane::QuadPlane(AP_AHRS &_ahrs) :
ahrs(_ahrs) ahrs(_ahrs)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);

View File

@ -3,7 +3,7 @@
#include <AP_Motors/AP_Motors.h> #include <AP_Motors/AP_Motors.h>
#include <AC_PID/AC_PID.h> #include <AC_PID/AC_PID.h>
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library #include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
#include <AP_InertialNav/AP_InertialNav.h> #include <AP_InertialNav/AP_InertialNav_NavEKF.h>
#include <AC_AttitudeControl/AC_PosControl.h> #include <AC_AttitudeControl/AC_PosControl.h>
#include <AC_WPNav/AC_WPNav.h> #include <AC_WPNav/AC_WPNav.h>
#include <AC_WPNav/AC_Loiter.h> #include <AC_WPNav/AC_Loiter.h>
@ -41,7 +41,7 @@ public:
friend class ModeQAutotune; friend class ModeQAutotune;
friend class ModeQAcro; friend class ModeQAcro;
QuadPlane(AP_AHRS_NavEKF &_ahrs); QuadPlane(AP_AHRS &_ahrs);
static QuadPlane *get_singleton() { static QuadPlane *get_singleton() {
return _singleton; return _singleton;
@ -186,7 +186,7 @@ public:
void set_q_assist_state(Q_ASSIST_STATE_ENUM state) {q_assist_state = state;}; void set_q_assist_state(Q_ASSIST_STATE_ENUM state) {q_assist_state = state;};
private: private:
AP_AHRS_NavEKF &ahrs; AP_AHRS &ahrs;
AP_Vehicle::MultiCopter aparm; AP_Vehicle::MultiCopter aparm;
AP_InertialNav_NavEKF inertial_nav{ahrs}; AP_InertialNav_NavEKF inertial_nav{ahrs};