Plane: set the PX4IO OVERRIDE_IMMEDIATE flag

This commit is contained in:
Andrew Tridgell 2014-11-07 11:30:30 +11:00
parent 0d2d63980d
commit 7356503e90
1 changed files with 3 additions and 0 deletions

View File

@ -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: