Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Quicktune C++ conversion (WIP) #27578

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
14 changes: 14 additions & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Winch/AP_Winch_config.h>
#include <AP_SurfaceDistance/AP_SurfaceDistance.h>
#include <AP_Quicktune/AP_Quicktune.h>

// Configuration
#include "defines.h"
Expand All @@ -83,6 +84,12 @@
#define MOTOR_CLASS AP_MotorsMulticopter
#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

#if MODE_AUTOROTATE_ENABLED == ENABLED
#include <AC_Autorotation/AC_Autorotation.h> // Autorotation controllers
#endif
Expand Down Expand Up @@ -487,6 +494,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 @@ -715,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
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 == ENABLED
// @Group: QUIK_
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
GOBJECT(quicktune, "QUIK_", 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
7 changes: 7 additions & 0 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ 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:
case AUX_FUNC::QUICKTUNE:
break;
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::ATTCON_ACCEL_LIM:
Expand Down Expand Up @@ -657,6 +658,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 @@ -194,6 +194,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 @@ -483,6 +488,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 @@ -1277,6 +1286,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
15 changes: 15 additions & 0 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -989,4 +992,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);
6 changes: 6 additions & 0 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1023,6 +1023,12 @@ const AP_Param::Info Plane::var_info[] = {
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
PARAM_VEHICLE_INFO,

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

AP_VAREND
};

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -359,6 +359,7 @@ class Parameters {
k_param_autotune_options,
k_param_takeoff_throttle_min,
k_param_takeoff_options,
k_param_quicktune,
};

AP_Int16 format_version;
Expand Down
9 changes: 9 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@
#if AP_EXTERNAL_CONTROL_ENABLED
#include "AP_ExternalControl_Plane.h"
#endif
#include <AP_Quicktune/AP_Quicktune.h>

#include <AC_PrecLand/AC_PrecLand_config.h>
#if AC_PRECLAND_ENABLED
Expand Down Expand Up @@ -319,6 +320,10 @@ class Plane : public AP_Vehicle {
ModeThermal mode_thermal;
#endif

#if AP_QUICKTUNE_ENABLED
AP_Quicktune quicktune;
#endif

// This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO
Mode *control_mode = &mode_initializing;
Expand Down Expand Up @@ -856,6 +861,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);
Expand Down
7 changes: 7 additions & 0 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
#if QAUTOTUNE_ENABLED
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
#endif
case AUX_FUNC::QUICKTUNE:
break;

case AUX_FUNC::SOARING:
Expand Down Expand Up @@ -456,6 +457,12 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break;
#endif

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

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
}
Expand Down
1 change: 0 additions & 1 deletion ArduPlane/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +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);

};

class RC_Channels_Plane : public RC_Channels
Expand Down
16 changes: 16 additions & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include "quadplane.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Quicktune/AP_Quicktune.h>

class AC_PosControl;
class AC_AttitudeControl_Multi;
Expand Down Expand Up @@ -141,6 +142,11 @@ class Mode
// true if voltage correction should be applied to throttle
virtual bool use_battery_compensation() const;

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

protected:

// subclasses override this to perform checks before entering the mode
Expand Down Expand Up @@ -312,6 +318,9 @@ class ModeGuided : public Mode

bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return true; }
#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif

private:
float active_radius_m;
Expand Down Expand Up @@ -649,6 +658,9 @@ class ModeQHover : public Mode
protected:

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

class ModeQLoiter : public Mode
Expand All @@ -675,6 +687,10 @@ friend class Plane;

bool _enter() override;
uint32_t last_target_loc_set_ms;

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

class ModeQLand : public Mode
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ def build(bld):
'AP_Follow',
'AC_PrecLand',
'AP_IRLock',
'AP_Quicktune',
],
)

Expand Down
Loading
Loading