mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning_Plane: Added PIDFF tuning sets
This commit is contained in:
parent
970d1a9f80
commit
64b4b2459b
|
@ -37,6 +37,9 @@ const uint8_t AP_Tuning_Plane::tuning_set_az[] = { TUNING_AZ_P, TU
|
||||||
const uint8_t AP_Tuning_Plane::tuning_set_rate_pitchDP[]= { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_P };
|
const uint8_t AP_Tuning_Plane::tuning_set_rate_pitchDP[]= { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_P };
|
||||||
const uint8_t AP_Tuning_Plane::tuning_set_rate_rollDP[]= { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_P };
|
const uint8_t AP_Tuning_Plane::tuning_set_rate_rollDP[]= { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_P };
|
||||||
const uint8_t AP_Tuning_Plane::tuning_set_rate_yawDP[]= { TUNING_RATE_YAW_D, TUNING_RATE_YAW_P };
|
const uint8_t AP_Tuning_Plane::tuning_set_rate_yawDP[]= { TUNING_RATE_YAW_D, TUNING_RATE_YAW_P };
|
||||||
|
const uint8_t AP_Tuning_Plane::tuning_set_dp_roll_pitch[] = { TUNING_RLL_D, TUNING_RLL_P, TUNING_PIT_D, TUNING_PIT_P };
|
||||||
|
const uint8_t AP_Tuning_Plane::tuning_set_pidff_roll[] = { TUNING_RLL_P, TUNING_RLL_I, TUNING_RLL_D, TUNING_RLL_FF };
|
||||||
|
const uint8_t AP_Tuning_Plane::tuning_set_pidff_pitch[] = { TUNING_PIT_P, TUNING_PIT_I, TUNING_PIT_D, TUNING_PIT_FF };
|
||||||
|
|
||||||
// macro to prevent getting the array length wrong
|
// macro to prevent getting the array length wrong
|
||||||
#define TUNING_ARRAY(v) ARRAY_SIZE(v), v
|
#define TUNING_ARRAY(v) ARRAY_SIZE(v), v
|
||||||
|
@ -53,6 +56,9 @@ const AP_Tuning_Plane::tuning_set AP_Tuning_Plane::tuning_sets[] = {
|
||||||
{ TUNING_SET_RATE_PITCHDP, TUNING_ARRAY(tuning_set_rate_pitchDP) },
|
{ TUNING_SET_RATE_PITCHDP, TUNING_ARRAY(tuning_set_rate_pitchDP) },
|
||||||
{ TUNING_SET_RATE_ROLLDP, TUNING_ARRAY(tuning_set_rate_rollDP) },
|
{ TUNING_SET_RATE_ROLLDP, TUNING_ARRAY(tuning_set_rate_rollDP) },
|
||||||
{ TUNING_SET_RATE_YAWDP, TUNING_ARRAY(tuning_set_rate_yawDP) },
|
{ TUNING_SET_RATE_YAWDP, TUNING_ARRAY(tuning_set_rate_yawDP) },
|
||||||
|
{ TUNING_SET_DP_ROLL_PITCH, TUNING_ARRAY(tuning_set_dp_roll_pitch) },
|
||||||
|
{ TUNING_SET_PIDFF_ROLL, TUNING_ARRAY(tuning_set_pidff_roll) },
|
||||||
|
{ TUNING_SET_PIDFF_PITCH, TUNING_ARRAY(tuning_set_pidff_pitch) },
|
||||||
{ 0, 0, nullptr }
|
{ 0, 0, nullptr }
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -94,6 +94,9 @@ private:
|
||||||
TUNING_SET_RATE_PITCHDP = 8,
|
TUNING_SET_RATE_PITCHDP = 8,
|
||||||
TUNING_SET_RATE_ROLLDP = 9,
|
TUNING_SET_RATE_ROLLDP = 9,
|
||||||
TUNING_SET_RATE_YAWDP = 10,
|
TUNING_SET_RATE_YAWDP = 10,
|
||||||
|
TUNING_SET_DP_ROLL_PITCH = 11,
|
||||||
|
TUNING_SET_PIDFF_ROLL = 12,
|
||||||
|
TUNING_SET_PIDFF_PITCH = 13,
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Float *get_param_pointer(uint8_t parm) override;
|
AP_Float *get_param_pointer(uint8_t parm) override;
|
||||||
|
@ -112,6 +115,9 @@ private:
|
||||||
static const uint8_t tuning_set_rate_pitchDP[];
|
static const uint8_t tuning_set_rate_pitchDP[];
|
||||||
static const uint8_t tuning_set_rate_rollDP[];
|
static const uint8_t tuning_set_rate_rollDP[];
|
||||||
static const uint8_t tuning_set_rate_yawDP[];
|
static const uint8_t tuning_set_rate_yawDP[];
|
||||||
|
static const uint8_t tuning_set_dp_roll_pitch[];
|
||||||
|
static const uint8_t tuning_set_pidff_roll[];
|
||||||
|
static const uint8_t tuning_set_pidff_pitch[];
|
||||||
|
|
||||||
// mask of what params have been set
|
// mask of what params have been set
|
||||||
uint64_t have_set;
|
uint64_t have_set;
|
||||||
|
|
Loading…
Reference in New Issue