Skip to content

Commit

Permalink
Copter: Added Quicktune
Browse files Browse the repository at this point in the history
disabled by default except in SITL
  • Loading branch information
MichelleRos authored and tridge committed Dec 17, 2024
1 parent b094390 commit d8d5f61
Show file tree
Hide file tree
Showing 7 changed files with 68 additions and 1 deletion.
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 @@ -831,6 +834,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
22 changes: 22 additions & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,15 @@
#include <AP_Winch/AP_Winch_config.h>
#include <AP_SurfaceDistance/AP_SurfaceDistance.h>

/*
default quicktune off in copter except for SITL
*/
#ifndef AP_QUICKTUNE_ENABLED
#define AP_QUICKTUNE_ENABLED CONFIG_HAL_BOARD == HAL_BOARD_SITL
#endif

#include <AP_Quicktune/AP_Quicktune.h>

// Configuration
#include "defines.h"
#include "config.h"
Expand All @@ -87,6 +96,12 @@
#include <AC_Autorotation/AC_Autorotation.h> // Autorotation controllers
#endif

#if FRAME_CONFIG == HELI_FRAME
// force quicktune off in heli until it has had testing
#undef AP_QUICKTUNE_ENABLED
#define AP_QUICKTUNE_ENABLED 0
#endif

#include "RC_Channel.h" // RC Channel Library

#include "GCS_Mavlink.h"
Expand Down Expand Up @@ -486,6 +501,10 @@ class Copter : public AP_Vehicle {
AC_Circle *circle_nav;
#endif

#if AP_QUICKTUNE_ENABLED
AP_Quicktune quicktune;
#endif

// System Timers
// --------------
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
Expand Down Expand Up @@ -716,6 +735,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
6 changes: 6 additions & 0 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -493,6 +493,12 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
#endif

#if AP_QUICKTUNE_ENABLED
// @Group: QWIK_
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
GOBJECT(quicktune, "QWIK_", AP_Quicktune),
#endif

// @Group: ATC_
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
GOBJECTVARPTR(attitude_control, "ATC_", &copter.attitude_control_var_info),
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -202,6 +202,7 @@ class Parameters {
k_param_circle_nav,
k_param_loiter_nav, // 105
k_param_custom_control,
k_param_quicktune,

// 110: Telemetry control
//
Expand Down
9 changes: 9 additions & 0 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,10 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::ARMDISARM_AIRMODE:
case AUX_FUNC::TURBINE_START:
case AUX_FUNC::FLIGHTMODE_PAUSE:
#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
break;
#endif
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::ATTCON_ACCEL_LIM:
case AUX_FUNC::ATTCON_FEEDFWD:
Expand Down Expand Up @@ -667,6 +670,12 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
// do nothing, used in tuning.cpp for transmitter based tuning
break;

#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
copter.quicktune.update_switch_pos(ch_flag);
break;
#endif

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
}
Expand Down
13 changes: 13 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,11 @@ class Mode {
virtual bool allows_weathervaning() const { return false; }
#endif

#if AP_QUICKTUNE_ENABLED
// does this mode support VTOL quicktune?
virtual bool supports_quicktune() const { return false; }
#endif

protected:

// helper functions
Expand Down Expand Up @@ -491,6 +496,10 @@ class ModeAltHold : public Mode {
const char *name() const override { return "ALT_HOLD"; }
const char *name4() const override { return "ALTH"; }

#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif

private:

};
Expand Down Expand Up @@ -1311,6 +1320,10 @@ class ModeLoiter : public Mode {
void precision_loiter_xy();
#endif

#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif

private:

#if AC_PRECLAND_ENABLED
Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ def build(bld):
'AP_Devo_Telem',
'AC_AutoTune',
'AP_KDECAN',
'AP_SurfaceDistance'
'AP_SurfaceDistance',
'AP_Quicktune',
],
)

Expand Down

0 comments on commit d8d5f61

Please sign in to comment.