mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: added some more tuning sets
This commit is contained in:
parent
35ef20b23a
commit
51877a20d6
@ -10,7 +10,7 @@ const AP_Param::GroupInfo AP_Tuning_Plane::var_info[] = {
|
||||
// @Param: PARAM
|
||||
// @DisplayName: Transmitter tuning parameter or set of parameters
|
||||
// @Description: This sets which parameter or set of parameters will be tuned. Values greater than 100 indicate a set of parameters rather than a single parameter. Parameters less than 50 are for QuadPlane vertical lift motors only.
|
||||
// @Values: 0:None,1:RateRollPI,2:RateRollP,3:RateRollI,4:RateRollD,5:RatePitchPI,6:RatePitchP,7:RatePitchI,8:RatePitchD,9:RateYawPI,10:RateYawP,11:RateYawI,12:RateYawD,13:AngleRollP,14:AnglePitchP,15:AngleYawP,16:PosXYP,17:PosZP,18:VelXYP,19:VelXYI,20:VelZP,21:AccelZP,22:AccelZI,23:AccelZD,50:FixedWingRollP,51:FixedWingRollI,52:FixedWingRollD,53:FixedWingRollFF,54:FixedWingPitchP,55:FixedWingPitchI,56:FixedWingPitchD,57:FixedWingPitchFF
|
||||
// @Values: 0:None,1:RateRollPI,2:RateRollP,3:RateRollI,4:RateRollD,5:RatePitchPI,6:RatePitchP,7:RatePitchI,8:RatePitchD,9:RateYawPI,10:RateYawP,11:RateYawI,12:RateYawD,13:AngleRollP,14:AnglePitchP,15:AngleYawP,16:PosXYP,17:PosZP,18:VelXYP,19:VelXYI,20:VelZP,21:AccelZP,22:AccelZI,23:AccelZD,50:FixedWingRollP,51:FixedWingRollI,52:FixedWingRollD,53:FixedWingRollFF,54:FixedWingPitchP,55:FixedWingPitchI,56:FixedWingPitchD,57:FixedWingPitchFF,101:Set_RateRollPitch,102:Set_RateRoll,103:Set_RatePitch,104:Set_RateYaw,105:Set_AngleRollPitch,106:Set_VelXY,107:Set_AccelZ
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("PARAM", 1, AP_Tuning_Plane, parmset, 0),
|
||||
|
||||
@ -28,6 +28,10 @@ const uint8_t AP_Tuning_Plane::tuning_set_rate_roll_pitch[] = { TUNING_RATE_ROLL
|
||||
TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI};
|
||||
const uint8_t AP_Tuning_Plane::tuning_set_rate_roll[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI };
|
||||
const uint8_t AP_Tuning_Plane::tuning_set_rate_pitch[] = { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI };
|
||||
const uint8_t AP_Tuning_Plane::tuning_set_rate_yaw[] = { TUNING_RATE_YAW_P, TUNING_RATE_YAW_I, TUNING_RATE_YAW_D };
|
||||
const uint8_t AP_Tuning_Plane::tuning_set_ang_roll_pitch[] = { TUNING_ANG_ROLL_P, TUNING_ANG_PITCH_P };
|
||||
const uint8_t AP_Tuning_Plane::tuning_set_vxy[] = { TUNING_VXY_P, TUNING_VXY_I };
|
||||
const uint8_t AP_Tuning_Plane::tuning_set_az[] = { TUNING_AZ_P, TUNING_AZ_I, TUNING_AZ_D };
|
||||
|
||||
// macro to prevent getting the array length wrong
|
||||
#define TUNING_ARRAY(v) ARRAY_SIZE(v), v
|
||||
|
@ -77,6 +77,10 @@ private:
|
||||
TUNING_SET_RATE_ROLL_PITCH = 1,
|
||||
TUNING_SET_RATE_ROLL = 2,
|
||||
TUNING_SET_RATE_PITCH = 3,
|
||||
TUNING_SET_RATE_YAW = 4,
|
||||
TUNING_SET_ANG_ROLL_PITCH = 5,
|
||||
TUNING_SET_VXY = 6,
|
||||
TUNING_SET_AZ = 7,
|
||||
};
|
||||
|
||||
AP_Float *get_param_pointer(uint8_t parm);
|
||||
@ -88,4 +92,8 @@ private:
|
||||
static const uint8_t tuning_set_rate_roll_pitch[];
|
||||
static const uint8_t tuning_set_rate_roll[];
|
||||
static const uint8_t tuning_set_rate_pitch[];
|
||||
static const uint8_t tuning_set_rate_yaw[];
|
||||
static const uint8_t tuning_set_ang_roll_pitch[];
|
||||
static const uint8_t tuning_set_vxy[];
|
||||
static const uint8_t tuning_set_az[];
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user