From 6df4d11d3f3bdab303ac2b1077e52f33b95130a6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 16 Apr 2016 18:52:12 +1000 Subject: [PATCH] AP_Motors: ensure OneShot125 is within 125 to 250usec --- libraries/AP_Motors/AP_Motors_Class.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 9bc4109bd7..84e591d88e 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -82,6 +82,16 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm) if (_pwm_type == PWM_TYPE_ONESHOT125) { // OneShot125 uses a PWM range from 125 to 250 usec pwm /= 8; + /* + OneShot125 ESCs can be confused by pulses below 125 or above + 250, making them fail the pulse type auto-detection. This + happens at least with BLHeli + */ + if (pwm < 125) { + pwm = 125; + } else if (pwm > 250) { + pwm = 250; + } } hal.rcout->write(chan, pwm); }