From ed488d518c97c0c63bcb694f6ef5b39f434769de Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 27 Jul 2024 13:23:50 +1000 Subject: [PATCH] Copter: switch to AP_QuickTune as pre-allocated object this simplifies the structure and use case at the cost of a bit more memory --- ArduCopter/Copter.cpp | 15 +++++++++++++++ ArduCopter/Copter.h | 5 ++++- ArduCopter/Parameters.cpp | 2 +- ArduCopter/RC_Channel.cpp | 25 +------------------------ ArduCopter/RC_Channel.h | 3 --- ArduCopter/mode.cpp | 6 ------ 6 files changed, 21 insertions(+), 35 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index b02628b1bd64a..6a25466b9c6c5 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -259,6 +259,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if HAL_BUTTON_ENABLED SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168), #endif +#if AP_QUICKTUNE_ENABLED + SCHED_TASK(update_quicktune, 40, 100, 171), +#endif }; void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, @@ -807,6 +810,18 @@ void Copter::update_altitude() #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 Copter::update_quicktune(void) +{ + quicktune.update(flightmode->supports_quicktune()); +} +#endif + // vehicle specific waypoint info helpers bool Copter::get_wp_distance_m(float &distance) const { diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index f49a0b474cb64..73af171614c00 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -495,7 +495,7 @@ class Copter : public AP_Vehicle { #endif #if AP_QUICKTUNE_ENABLED - AP_Quicktune *quicktune; + AP_Quicktune quicktune; #endif // System Timers @@ -726,6 +726,9 @@ class Copter : public AP_Vehicle { bool get_wp_bearing_deg(float &bearing) const override; bool get_wp_crosstrack_error_m(float &xtrack_error) const override; bool get_rate_ef_targets(Vector3f& rate_ef_targets) const override; +#if AP_QUICKTUNE_ENABLED + void update_quicktune(void); +#endif // Attitude.cpp void update_throttle_hover(); diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 724816c842568..1788835917cec 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -496,7 +496,7 @@ const AP_Param::Info Copter::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 // @Group: ATC_ diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 0df53f3eec6ac..42cfae8cdd0f8 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -651,7 +651,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc #endif #if AP_QUICKTUNE_ENABLED case AUX_FUNC::QUICKTUNE: - do_aux_function_quicktune(ch_flag); + copter.quicktune.update_switch_pos(ch_flag); break; #endif @@ -691,29 +691,6 @@ void RC_Channel_Copter::do_aux_function_change_force_flying(const AuxSwitchPos c } } -#if AP_QUICKTUNE_ENABLED -// called on any Quicktune Aux function change -void RC_Channel_Copter::do_aux_function_quicktune(const AuxSwitchPos ch_flag) -{ - if (copter.quicktune == nullptr && !copter.arming.is_armed()) { - //first call, allocate quicktune object - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Quicktune: Initialised."); - copter.quicktune = NEW_NOTHROW AP_Quicktune(); - if (copter.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(copter.quicktune, copter.quicktune->var_info); - } else if (copter.quicktune == nullptr && copter.arming.is_armed()){ - GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Quicktune: Must be disarmed to initialise."); - } - if (copter.quicktune != nullptr) { - copter.quicktune->update_switch_pos(ch_flag); - } -} -#endif - // save_trim - adds roll and pitch trims from the radio to ahrs void Copter::save_trim() { diff --git a/ArduCopter/RC_Channel.h b/ArduCopter/RC_Channel.h index c7fd796b3ad4b..b0ba3ebb1492f 100644 --- a/ArduCopter/RC_Channel.h +++ b/ArduCopter/RC_Channel.h @@ -20,9 +20,6 @@ class RC_Channel_Copter : public RC_Channel const AuxSwitchPos ch_flag); void do_aux_function_change_air_mode(const AuxSwitchPos ch_flag); void do_aux_function_change_force_flying(const AuxSwitchPos ch_flag); -#if AP_QUICKTUNE_ENABLED - void do_aux_function_quicktune(const AuxSwitchPos ch_flag); -#endif // called when the mode switch changes position: void mode_switch_changed(modeswitch_pos_t new_pos) override; diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index f4aba15a97fc5..ce191b0c1ef08 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -425,12 +425,6 @@ void Copter::update_flight_mode() #endif flightmode->run(); - -#if AP_QUICKTUNE_ENABLED - if (quicktune != nullptr && flightmode->supports_quicktune()) { - quicktune->update(); - } -#endif } // exit_mode - high level call to organise cleanup as a flight mode is exited