mirror of https://github.com/ArduPilot/ardupilot
Plane: Add Q_FWD_THR_GAIN to table of transmitter tuning parameters
This commit is contained in:
parent
6ad7588857
commit
f834d4730b
|
@ -94,6 +94,7 @@ const AP_Tuning_Plane::tuning_name AP_Tuning_Plane::tuning_names[] = {
|
||||||
{ TUNING_PIT_I, "PitchI" },
|
{ TUNING_PIT_I, "PitchI" },
|
||||||
{ TUNING_PIT_D, "PitchD" },
|
{ TUNING_PIT_D, "PitchD" },
|
||||||
{ TUNING_PIT_FF, "PitchFF" },
|
{ TUNING_PIT_FF, "PitchFF" },
|
||||||
|
{ TUNING_Q_FWD_THR, "QModeFwdThr" },
|
||||||
{ TUNING_NONE, nullptr }
|
{ TUNING_NONE, nullptr }
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -190,6 +191,9 @@ AP_Float *AP_Tuning_Plane::get_param_pointer(uint8_t parm)
|
||||||
|
|
||||||
case TUNING_RATE_YAW_FF:
|
case TUNING_RATE_YAW_FF:
|
||||||
return &plane.quadplane.attitude_control->get_rate_yaw_pid().ff();
|
return &plane.quadplane.attitude_control->get_rate_yaw_pid().ff();
|
||||||
|
|
||||||
|
case TUNING_Q_FWD_THR:
|
||||||
|
return &plane.quadplane.q_fwd_thr_gain;
|
||||||
#endif // HAL_QUADPLANE_ENABLED
|
#endif // HAL_QUADPLANE_ENABLED
|
||||||
|
|
||||||
// fixed wing tuning parameters
|
// fixed wing tuning parameters
|
||||||
|
|
|
@ -76,6 +76,8 @@ private:
|
||||||
TUNING_PIT_I = 55,
|
TUNING_PIT_I = 55,
|
||||||
TUNING_PIT_D = 56,
|
TUNING_PIT_D = 56,
|
||||||
TUNING_PIT_FF = 57,
|
TUNING_PIT_FF = 57,
|
||||||
|
|
||||||
|
TUNING_Q_FWD_THR = 58,
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue