From 933266e5b23e58b4dee464ee6e48077f9455743f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 27 Jul 2024 13:51:41 +1000 Subject: [PATCH] Plane: convert to new quicktune approach --- ArduPlane/ArduPlane.cpp | 15 +++++++++++++++ ArduPlane/Attitude.cpp | 5 ----- ArduPlane/Parameters.cpp | 2 +- ArduPlane/Plane.h | 6 +++++- ArduPlane/RC_Channel.cpp | 25 +------------------------ ArduPlane/RC_Channel.h | 3 --- 6 files changed, 22 insertions(+), 34 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index bc6d28fbfaa8a..7b55db8c2a9e6 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -139,6 +139,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #if AC_PRECLAND_ENABLED SCHED_TASK(precland_update, 400, 50, 160), #endif +#if AP_QUICKTUNE_ENABLED + SCHED_TASK(update_quicktune, 40, 100, 163), +#endif }; void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, @@ -979,4 +982,16 @@ void Plane::precland_update(void) } #endif +#if AP_QUICKTUNE_ENABLED +/* + update AP_Quicktune object. We pass the supports_quicktune() method + in so that quicktune can detect if the user changes to a + non-quicktune capable mode while tuning and the gains can be reverted + */ +void Plane::update_quicktune(void) +{ + quicktune.update(control_mode->supports_quicktune()); +} +#endif + AP_HAL_MAIN_CALLBACKS(&plane); diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index a57a4bc68349c..0996a50b725ab 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -424,11 +424,6 @@ void Plane::stabilize() #endif } else { plane.control_mode->run(); -#if AP_QUICKTUNE_ENABLED - if (plane.quicktune != nullptr && control_mode->supports_quicktune()) { - plane.quicktune->update(); - } -#endif } /* diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 99848f2a863b5..3842b3389f3c3 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1000,7 +1000,7 @@ const AP_Param::Info Plane::var_info[] = { #if AP_QUICKTUNE_ENABLED == ENABLED // @Group: QUIK_ // @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp - GOBJECTPTR(quicktune, "QUIK_", AP_Quicktune), + GOBJECT(quicktune, "QUIK_", AP_Quicktune), #endif AP_VAREND diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 11bcbad0fdf00..6760a2c3e0d6b 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -307,7 +307,7 @@ class Plane : public AP_Vehicle { #endif #if AP_QUICKTUNE_ENABLED - AP_Quicktune *quicktune; + AP_Quicktune quicktune; #endif // This is the state of the flight control system @@ -846,6 +846,10 @@ class Plane : public AP_Vehicle { static const TerrainLookupTable Terrain_lookup[]; #endif +#if AP_QUICKTUNE_ENABLED + void update_quicktune(void); +#endif + // Attitude.cpp void adjust_nav_pitch_throttle(void); void update_load_factor(void); diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 4a246c09ca984..3b9d37e0eb477 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -442,7 +442,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch #if AP_QUICKTUNE_ENABLED case AUX_FUNC::QUICKTUNE: - do_aux_function_quicktune(ch_flag); + plane.quicktune.update_switch_pos(ch_flag); break; #endif @@ -452,26 +452,3 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch return true; } - -#if AP_QUICKTUNE_ENABLED -// called on any Quicktune Aux function change -void RC_Channel_Plane::do_aux_function_quicktune(const AuxSwitchPos ch_flag) -{ - if (plane.quicktune == nullptr && !plane.arming.is_armed()) { - //first call, allocate quicktune object - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Quicktune: Initialised."); - plane.quicktune = NEW_NOTHROW AP_Quicktune(); - if (plane.quicktune == nullptr) { - // Can't use BoardConfig error as this might happen while flying. - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Quicktune: unable to allocate."); - return; - } - AP_Param::load_object_from_eeprom(plane.quicktune, plane.quicktune->var_info); - } else if (plane.quicktune == nullptr && plane.arming.is_armed()){ - GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Quicktune: Must be disarmed to initialise."); - } - if (plane.quicktune != nullptr) { - plane.quicktune->update_switch_pos(ch_flag); - } -} -#endif diff --git a/ArduPlane/RC_Channel.h b/ArduPlane/RC_Channel.h index a437ef963d06d..e9b4804aac545 100644 --- a/ArduPlane/RC_Channel.h +++ b/ArduPlane/RC_Channel.h @@ -30,9 +30,6 @@ class RC_Channel_Plane : public RC_Channel void do_aux_function_soaring_3pos(AuxSwitchPos ch_flag); void do_aux_function_flare(AuxSwitchPos ch_flag); -#if AP_QUICKTUNE_ENABLED - void do_aux_function_quicktune(const AuxSwitchPos ch_flag); -#endif }; class RC_Channels_Plane : public RC_Channels