Sub: Send invalid PWM to servo rail before rebooting

This corrects a previous attempt at doing the same
This commit is contained in:
Jacob Walser 2016-12-14 19:10:29 -05:00 committed by Andrew Tridgell
parent d237887d08
commit 173ee85ac7
1 changed files with 2 additions and 1 deletions

View File

@ -1513,7 +1513,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// For that matter, send an invalid signal to all channels to prevent undesired/unexpected behavior
hal.rcout->cork();
for(int i=0; i<RC_MAX_CHANNELS; i++ ) {
hal.rcout->write(i, 0);
// Set to 1 because 0 is interpreted as flag to ignore update
hal.rcout->write(i, 1);
}
hal.rcout->push();