mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_HAL_ChibiOS: reversible DShot fix
Co-authored-by: Andy Piper <github@andypiper.com>
This commit is contained in:
parent
df9679c73a
commit
596893b199
@ -1404,7 +1404,7 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us)
|
||||
pwm = constrain_int16(pwm, 1000, 2000);
|
||||
uint16_t value = MIN(2 * (pwm - 1000), 1999);
|
||||
|
||||
if (chan_mask & (_reversible_mask>>chan_offset)) {
|
||||
if ((chan_mask & _reversible_mask) != 0) {
|
||||
// this is a DShot-3D output, map so that 1500 PWM is zero throttle reversed
|
||||
if (value < 1000) {
|
||||
value = 1999 - value;
|
||||
|
Loading…
Reference in New Issue
Block a user