Rover: cork and push servo outputs

SRV_Channels API makes it easy to sync all PWM channels at once. This is
the support needed for it to work properly on Rovers.
This commit is contained in:
Georgii Staroselskii 2017-05-29 15:51:16 +03:00
parent b09ebbb891
commit 541538fbae

View File

@ -353,7 +353,9 @@ void Rover::set_servos(void) {
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
// send values to the PWM timers for output
// ----------------------------------------
hal.rcout->cork();
SRV_Channels::output_ch_all();
hal.rcout->push();
#endif
}