mirror of https://github.com/ArduPilot/ardupilot
ACM : Upped Yaw Limit to 2200
This commit is contained in:
parent
7ac4d06d3f
commit
bd17c23e7e
|
@ -343,7 +343,7 @@ get_rate_yaw(int32_t target_rate)
|
||||||
return output;
|
return output;
|
||||||
#else
|
#else
|
||||||
// output control:
|
// output control:
|
||||||
int16_t yaw_limit = 2000 + abs(g.rc_4.control_in);
|
int16_t yaw_limit = 2200 + abs(g.rc_4.control_in);
|
||||||
// smoother Yaw control:
|
// smoother Yaw control:
|
||||||
return constrain(output, -yaw_limit, yaw_limit);
|
return constrain(output, -yaw_limit, yaw_limit);
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue