mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: adjust for change to AC_PID
This commit is contained in:
parent
2086b591a2
commit
4a4fc8ab06
@ -116,15 +116,15 @@ void Copter::tuning() {
|
||||
break;
|
||||
|
||||
case TUNING_RATE_PITCH_FF:
|
||||
attitude_control->get_heli_rate_pitch_pid().ff(tuning_value);
|
||||
attitude_control->get_rate_pitch_pid().ff(tuning_value);
|
||||
break;
|
||||
|
||||
case TUNING_RATE_ROLL_FF:
|
||||
attitude_control->get_heli_rate_roll_pid().ff(tuning_value);
|
||||
attitude_control->get_rate_roll_pid().ff(tuning_value);
|
||||
break;
|
||||
|
||||
case TUNING_RATE_YAW_FF:
|
||||
attitude_control->get_heli_rate_yaw_pid().ff(tuning_value);
|
||||
attitude_control->get_rate_yaw_pid().ff(tuning_value);
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user