mirror of https://github.com/ArduPilot/ardupilot
AC_AutoTune: fix tradheli bug with load gain set
This commit is contained in:
parent
577eefd393
commit
d65819bf03
|
@ -519,7 +519,7 @@ void AC_AutoTune_Heli::load_test_gains()
|
|||
// load gains
|
||||
void AC_AutoTune_Heli::load_gain_set(AxisType s_axis, float rate_p, float rate_i, float rate_d, float rate_ff, float angle_p, float max_accel, float rate_fltt, float rate_flte, float smax)
|
||||
{
|
||||
switch (axis) {
|
||||
switch (s_axis) {
|
||||
case ROLL:
|
||||
attitude_control->get_rate_roll_pid().kP(rate_p);
|
||||
attitude_control->get_rate_roll_pid().kI(rate_i);
|
||||
|
|
Loading…
Reference in New Issue