mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
TradHeli - increase max yaw input to 45 degrees
This commit is contained in:
parent
ed5db98522
commit
ab0e1d7632
@ -62,8 +62,13 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
// angle error
|
||||
target_angle = wrap_180(target_angle - dcm.yaw_sensor);
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME // cannot use rate control for helicopters
|
||||
// limit the error we're feeding to the PID
|
||||
target_angle = constrain(target_angle, -4500, 4500);
|
||||
#else
|
||||
// limit the error we're feeding to the PID
|
||||
target_angle = constrain(target_angle, -2000, 2000);
|
||||
#endif
|
||||
|
||||
// conver to desired Rate:
|
||||
int32_t target_rate = g.pi_stabilize_yaw.get_p(target_angle);
|
||||
|
Loading…
Reference in New Issue
Block a user