mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
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:
parent
34e611be59
commit
eed08fb8cd
@ -329,7 +329,9 @@ void Rover::set_servos(void) {
|
|||||||
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
||||||
// send values to the PWM timers for output
|
// send values to the PWM timers for output
|
||||||
// ----------------------------------------
|
// ----------------------------------------
|
||||||
|
hal.rcout->cork();
|
||||||
SRV_Channels::output_ch_all();
|
SRV_Channels::output_ch_all();
|
||||||
|
hal.rcout->push();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user