mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
ACM: TradHeli
Removing this "throttle" output restriction for TradHelis.
This commit is contained in:
parent
92cd631ce5
commit
637c9a1a72
@ -203,9 +203,10 @@ static void init_disarm_motors()
|
|||||||
static void
|
static void
|
||||||
set_servos_4()
|
set_servos_4()
|
||||||
{
|
{
|
||||||
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
// temp fix for bad attitude
|
// temp fix for bad attitude
|
||||||
g.rc_3.servo_out = min(g.rc_3.servo_out, 800);
|
g.rc_3.servo_out = min(g.rc_3.servo_out, 800);
|
||||||
|
#endif
|
||||||
motors.output();
|
motors.output();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user