mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 09:13:57 -04:00
AC_AutoTune: Fix issue with parameters in quadplane
This commit is contained in:
parent
54bdde8845
commit
e780687f5f
@ -84,22 +84,9 @@
|
||||
|
||||
// second table of user settable parameters for quadplanes, this
|
||||
// allows us to go beyond the 64 parameter limit
|
||||
const AP_Param::GroupInfo AC_AutoTune::var_info[] = {
|
||||
// @Param: AXES
|
||||
// @DisplayName: Autotune axis bitmask
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("AXES", 1, AC_AutoTune, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
|
||||
|
||||
// Indices 2 and 3 where AGGR and MIN_D. These were moved to the Multi SubClass
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AC_AutoTune::AC_AutoTune()
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
// autotune_init - should be called when autotune mode is selected
|
||||
|
@ -61,9 +61,6 @@ public:
|
||||
axes_completed = 0;
|
||||
}
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
|
||||
// axis that can be tuned
|
||||
|
@ -46,42 +46,48 @@
|
||||
#define AUTOTUNE_SEQ_BITMASK_MAX_GAIN 8
|
||||
|
||||
const AP_Param::GroupInfo AC_AutoTune_Heli::var_info[] = {
|
||||
AP_NESTEDGROUPINFO(AC_AutoTune, 0),
|
||||
|
||||
// @Param: AXES
|
||||
// @DisplayName: Autotune axis bitmask
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("AXES", 1, AC_AutoTune_Heli, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
|
||||
|
||||
// @Param: SEQ
|
||||
// @DisplayName: AutoTune Sequence Bitmask
|
||||
// @Description: 2-byte bitmask to select what tuning should be performed. Max gain automatically performed if Rate D is selected. Values: 7:All,1:VFF Only,2:Rate D Only,4:Angle P Only,8:Max Gain Only,3:VFF and Rate D (incl max gain),5:VFF and Angle P,13:VFF max gain and angle P
|
||||
// @Bitmask: 0:VFF,1:Rate D,2:Angle P,3:Max Gain Only
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SEQ", 1, AC_AutoTune_Heli, seq_bitmask, 5),
|
||||
AP_GROUPINFO("SEQ", 2, AC_AutoTune_Heli, seq_bitmask, 5),
|
||||
|
||||
// @Param: MIN_FRQ
|
||||
// @DisplayName: AutoTune minimum sweep frequency
|
||||
// @Description: Defines the start frequency for sweeps and dwells
|
||||
// @Range: 10 30
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MIN_FRQ", 2, AC_AutoTune_Heli, min_sweep_freq, 10.0f),
|
||||
AP_GROUPINFO("MIN_FRQ", 3, AC_AutoTune_Heli, min_sweep_freq, 10.0f),
|
||||
|
||||
// @Param: MAX_FRQ
|
||||
// @DisplayName: AutoTune maximum sweep frequency
|
||||
// @Description: Defines the end frequency for sweeps and dwells
|
||||
// @Range: 50 120
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MAX_FRQ", 3, AC_AutoTune_Heli, max_sweep_freq, 70.0f),
|
||||
AP_GROUPINFO("MAX_FRQ", 4, AC_AutoTune_Heli, max_sweep_freq, 70.0f),
|
||||
|
||||
// @Param: MAX_GN
|
||||
// @DisplayName: AutoTune maximum response gain
|
||||
// @Description: Defines the response gain (output/input) to tune
|
||||
// @Range: 1 2.5
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MAX_GN", 4, AC_AutoTune_Heli, max_resp_gain, 1.4f),
|
||||
AP_GROUPINFO("MAX_GN", 5, AC_AutoTune_Heli, max_resp_gain, 1.4f),
|
||||
|
||||
// @Param: VELXY_P
|
||||
// @DisplayName: AutoTune velocity xy P gain
|
||||
// @Description: Velocity xy P gain used to hold position during Max Gain, Rate P, and Rate D frequency sweeps
|
||||
// @Range: 0 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("VELXY_P", 5, AC_AutoTune_Heli, vel_hold_gain, 0.1f),
|
||||
AP_GROUPINFO("VELXY_P", 6, AC_AutoTune_Heli, vel_hold_gain, 0.1f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -37,21 +37,27 @@
|
||||
#include "AC_AutoTune_Multi.h"
|
||||
|
||||
const AP_Param::GroupInfo AC_AutoTune_Multi::var_info[] = {
|
||||
AP_NESTEDGROUPINFO(AC_AutoTune, 0),
|
||||
|
||||
// @Param: AXES
|
||||
// @DisplayName: Autotune axis bitmask
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("AXES", 1, AC_AutoTune_Multi, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
|
||||
|
||||
// @Param: AGGR
|
||||
// @DisplayName: Autotune aggressiveness
|
||||
// @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
|
||||
// @Range: 0.05 0.10
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("AGGR", 1, AC_AutoTune_Multi, aggressiveness, 0.1f),
|
||||
AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.1f),
|
||||
|
||||
// @Param: MIN_D
|
||||
// @DisplayName: AutoTune minimum D
|
||||
// @Description: Defines the minimum D gain
|
||||
// @Range: 0.001 0.006
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MIN_D", 2, AC_AutoTune_Multi, min_d, 0.001f),
|
||||
AP_GROUPINFO("MIN_D", 3, AC_AutoTune_Multi, min_d, 0.001f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user