mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
TradHeli - increase max yaw input to 45 degrees
This commit is contained in:
parent
385828824d
commit
57e5eee8c8
@ -62,8 +62,13 @@ get_stabilize_yaw(int32_t target_angle)
|
|||||||
// angle error
|
// angle error
|
||||||
target_angle = wrap_180(target_angle - dcm.yaw_sensor);
|
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
|
// limit the error we're feeding to the PID
|
||||||
target_angle = constrain(target_angle, -2000, 2000);
|
target_angle = constrain(target_angle, -2000, 2000);
|
||||||
|
#endif
|
||||||
|
|
||||||
// conver to desired Rate:
|
// conver to desired Rate:
|
||||||
int32_t target_rate = g.pi_stabilize_yaw.get_p(target_angle);
|
int32_t target_rate = g.pi_stabilize_yaw.get_p(target_angle);
|
||||||
|
Loading…
Reference in New Issue
Block a user