From a731caa4abd21b131aa209edf9dac21448c1d31a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 16 Apr 2016 18:52:31 +1000 Subject: [PATCH] HLA_PX4: prevent timer disturbance in oneshot mode --- libraries/AP_HAL_PX4/RCOutput.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 342e4ead5f..2ad060219b 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -163,6 +163,11 @@ void PX4RCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz) */ void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) { + if (_output_mode == MODE_PWM_ONESHOT) { + // changing the output frequency makes no sense in oneshot + // mode, and can disturb the timers causing spurious glitches + return; + } // greater than 400 doesn't give enough room at higher periods for // the down pulse if (freq_hz > 400) { @@ -528,6 +533,10 @@ bool PX4RCOutput::enable_sbus_out(uint16_t rate_hz) */ void PX4RCOutput::set_output_mode(enum output_mode mode) { + if (_output_mode == mode) { + // no change + return; + } _output_mode = mode; if (_output_mode == MODE_PWM_ONESHOT) { ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 1);