mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Opening up the Yaw Rate constraint for Trad Heli.
This commit is contained in:
parent
e2496181ff
commit
c5916a8b4d
@ -255,7 +255,7 @@ get_rate_yaw(int32_t target_rate)
|
|||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
int16_t yaw_limit = 2800 + abs(g.rc_4.control_in);
|
int16_t yaw_limit = 4500;
|
||||||
#else
|
#else
|
||||||
int16_t yaw_limit = 1400 + abs(g.rc_4.control_in);
|
int16_t yaw_limit = 1400 + abs(g.rc_4.control_in);
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user