From 541538fbae61ae07e0e742af99ee492c7b0a4087 Mon Sep 17 00:00:00 2001 From: Georgii Staroselskii Date: Mon, 29 May 2017 15:51:16 +0300 Subject: [PATCH] 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. --- APMrover2/Steering.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/APMrover2/Steering.cpp b/APMrover2/Steering.cpp index 32024914ea..f6f30f4f93 100644 --- a/APMrover2/Steering.cpp +++ b/APMrover2/Steering.cpp @@ -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 }