From 6440cabffa9899196acbe33d08847bc7b79948b1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 19 Jul 2023 14:07:31 +0100 Subject: [PATCH] Copter: use base class AC_AttitudeControl object --- ArduCopter/Copter.h | 8 +------- ArduCopter/mode.h | 2 +- 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 0827e2a09ca9e7..e702b96dbb10c1 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -77,12 +77,6 @@ #include "defines.h" #include "config.h" -#if FRAME_CONFIG == HELI_FRAME - #define AC_AttitudeControl_t AC_AttitudeControl_Heli -#else - #define AC_AttitudeControl_t AC_AttitudeControl_Multi -#endif - #if FRAME_CONFIG == HELI_FRAME #define MOTOR_CLASS AP_MotorsHeli #else @@ -485,7 +479,7 @@ class Copter : public AP_Vehicle { // Attitude, Position and Waypoint navigation objects // To-Do: move inertial nav up or other navigation variables down here - AC_AttitudeControl_t *attitude_control; + AC_AttitudeControl *attitude_control; AC_PosControl *pos_control; AC_WPNav *wp_nav; AC_Loiter *loiter_nav; diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 3de08e4766a69f..fb787077b90594 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -241,7 +241,7 @@ class Mode { AC_PosControl *&pos_control; AP_InertialNav &inertial_nav; AP_AHRS &ahrs; - AC_AttitudeControl_t *&attitude_control; + AC_AttitudeControl *&attitude_control; MOTOR_CLASS *&motors; RC_Channel *&channel_roll; RC_Channel *&channel_pitch;