Plane: Added Quicktune

replaces QAUTOTUNE in default build
This commit is contained in:
Michelle Rossouw 2024-07-27 15:52:11 +10:00 committed by Andrew Tridgell
parent edcddcb82e
commit 43fdc9ce19
9 changed files with 63 additions and 2 deletions

View File

@ -139,6 +139,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if AC_PRECLAND_ENABLED #if AC_PRECLAND_ENABLED
SCHED_TASK(precland_update, 400, 50, 160), SCHED_TASK(precland_update, 400, 50, 160),
#endif #endif
#if AP_QUICKTUNE_ENABLED
SCHED_TASK(update_quicktune, 40, 100, 163),
#endif
}; };
void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
@ -1025,4 +1028,16 @@ void Plane::precland_update(void)
} }
#endif #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); AP_HAL_MAIN_CALLBACKS(&plane);

View File

@ -1038,6 +1038,12 @@ const AP_Param::Info Plane::var_info[] = {
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
PARAM_VEHICLE_INFO, PARAM_VEHICLE_INFO,
#if AP_QUICKTUNE_ENABLED
// @Group: QWIK_
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
GOBJECT(quicktune, "QWIK_", AP_Quicktune),
#endif
AP_VAREND AP_VAREND
}; };

View File

@ -362,6 +362,7 @@ public:
k_param_takeoff_throttle_idle, k_param_takeoff_throttle_idle,
k_param_pullup = 270, k_param_pullup = 270,
k_param_quicktune,
}; };
AP_Int16 format_version; AP_Int16 format_version;

View File

@ -330,6 +330,10 @@ private:
ModeThermal mode_thermal; ModeThermal mode_thermal;
#endif #endif
#if AP_QUICKTUNE_ENABLED
AP_Quicktune quicktune;
#endif
// This is the state of the flight control system // This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO // There are multiple states defined such as MANUAL, FBW-A, AUTO
Mode *control_mode = &mode_initializing; Mode *control_mode = &mode_initializing;
@ -875,6 +879,10 @@ private:
static const TerrainLookupTable Terrain_lookup[]; static const TerrainLookupTable Terrain_lookup[];
#endif #endif
#if AP_QUICKTUNE_ENABLED
void update_quicktune(void);
#endif
// Attitude.cpp // Attitude.cpp
void adjust_nav_pitch_throttle(void); void adjust_nav_pitch_throttle(void);
void update_load_factor(void); void update_load_factor(void);

View File

@ -1,6 +1,7 @@
#include "Plane.h" #include "Plane.h"
#include "RC_Channel.h" #include "RC_Channel.h"
#include "qautotune.h"
// defining these two macros and including the RC_Channels_VarInfo // defining these two macros and including the RC_Channels_VarInfo
// header defines the parameter information common to all vehicle // header defines the parameter information common to all vehicle
@ -176,6 +177,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
#endif #endif
#if QAUTOTUNE_ENABLED #if QAUTOTUNE_ENABLED
case AUX_FUNC::AUTOTUNE_TEST_GAINS: case AUX_FUNC::AUTOTUNE_TEST_GAINS:
#endif
#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
#endif #endif
break; break;
@ -458,6 +462,12 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break; break;
#endif #endif
#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
plane.quicktune.update_switch_pos(ch_flag);
break;
#endif
default: default:
return RC_Channel::do_aux_function(ch_option, ch_flag); return RC_Channel::do_aux_function(ch_option, ch_flag);
} }

View File

@ -30,7 +30,6 @@ private:
void do_aux_function_soaring_3pos(AuxSwitchPos ch_flag); void do_aux_function_soaring_3pos(AuxSwitchPos ch_flag);
void do_aux_function_flare(AuxSwitchPos ch_flag); void do_aux_function_flare(AuxSwitchPos ch_flag);
}; };
class RC_Channels_Plane : public RC_Channels class RC_Channels_Plane : public RC_Channels

View File

@ -11,6 +11,12 @@
#include <AP_Mission/AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include "pullup.h" #include "pullup.h"
#ifndef AP_QUICKTUNE_ENABLED
#define AP_QUICKTUNE_ENABLED HAL_QUADPLANE_ENABLED
#endif
#include <AP_Quicktune/AP_Quicktune.h>
class AC_PosControl; class AC_PosControl;
class AC_AttitudeControl_Multi; class AC_AttitudeControl_Multi;
class AC_Loiter; class AC_Loiter;
@ -142,6 +148,11 @@ public:
// true if voltage correction should be applied to throttle // true if voltage correction should be applied to throttle
virtual bool use_battery_compensation() const; 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: protected:
// subclasses override this to perform checks before entering the mode // subclasses override this to perform checks before entering the mode
@ -325,6 +336,9 @@ protected:
bool _enter() override; bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return true; } 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: private:
float active_radius_m; float active_radius_m;
@ -662,6 +676,9 @@ public:
protected: protected:
bool _enter() override; bool _enter() override;
#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif
}; };
class ModeQLoiter : public Mode class ModeQLoiter : public Mode
@ -688,6 +705,10 @@ protected:
bool _enter() override; bool _enter() override;
uint32_t last_target_loc_set_ms; uint32_t last_target_loc_set_ms;
#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif
}; };
class ModeQLand : public Mode class ModeQLand : public Mode

View File

@ -8,7 +8,7 @@
#include "quadplane.h" #include "quadplane.h"
#ifndef QAUTOTUNE_ENABLED #ifndef QAUTOTUNE_ENABLED
#define QAUTOTUNE_ENABLED HAL_QUADPLANE_ENABLED #define QAUTOTUNE_ENABLED (HAL_QUADPLANE_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif #endif
#if QAUTOTUNE_ENABLED #if QAUTOTUNE_ENABLED

View File

@ -27,6 +27,7 @@ def build(bld):
'AP_Follow', 'AP_Follow',
'AC_PrecLand', 'AC_PrecLand',
'AP_IRLock', 'AP_IRLock',
'AP_Quicktune',
], ],
) )