mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: set the PX4IO OVERRIDE_IMMEDIATE flag
This commit is contained in:
parent
0d2d63980d
commit
7356503e90
@ -269,6 +269,9 @@ static bool setup_failsafe_mixing(void)
|
||||
ioctl(px4io_fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values);
|
||||
ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0);
|
||||
|
||||
// setup for immediate manual control if FMU dies
|
||||
ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 1);
|
||||
|
||||
ret = true;
|
||||
|
||||
failed:
|
||||
|
Loading…
Reference in New Issue
Block a user