Skip to content

Commit

Permalink
Copter: switch to AP_QuickTune as pre-allocated object
Browse files Browse the repository at this point in the history
this simplifies the structure and use case at the cost of a bit more
memory
  • Loading branch information
tridge committed Jul 27, 2024
1 parent a324777 commit ed488d5
Show file tree
Hide file tree
Showing 6 changed files with 21 additions and 35 deletions.
15 changes: 15 additions & 0 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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
{
Expand Down
5 changes: 4 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -495,7 +495,7 @@ class Copter : public AP_Vehicle {
#endif

#if AP_QUICKTUNE_ENABLED
AP_Quicktune *quicktune;
AP_Quicktune quicktune;
#endif

// System Timers
Expand Down Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_
Expand Down
25 changes: 1 addition & 24 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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()
{
Expand Down
3 changes: 0 additions & 3 deletions ArduCopter/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
6 changes: 0 additions & 6 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit ed488d5

Please sign in to comment.