mirror of https://github.com/ArduPilot/ardupilot
Plane: check channel space before sending servo output raw in SITL CPU failsafe
This commit is contained in:
parent
b3ff81648b
commit
ab557662cc
|
@ -106,7 +106,10 @@ void Plane::failsafe_check(void)
|
||||||
// in SITL we send through the servo outputs so we can verify
|
// in SITL we send through the servo outputs so we can verify
|
||||||
// we're manipulating surfaces
|
// we're manipulating surfaces
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
gcs().chan(0)->send_servo_output_raw();
|
GCS_MAVLINK *chan = gcs().chan(0);
|
||||||
|
if (HAVE_PAYLOAD_SPACE(chan->get_chan(), SERVO_OUTPUT_RAW)) {
|
||||||
|
chan->send_servo_output_raw();
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue