diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 39708a11c0..a899b35bca 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -200,7 +200,7 @@ public: * The mask uses servo channel numbering */ void set_reversed_mask(uint16_t chanmask) override; - uint16_t get_reversed_mask() override { return _reversed_mask; } + uint16_t get_reversed_mask() override { return _reversed_mask << chan_offset; } /* mark escs as active for the purpose of sending dshot commands diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index 13a5578c02..3fddedc1a4 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -98,7 +98,7 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman DshotCommandPacket pkt; pkt.command = command; - pkt.chan = chan + chan_offset; + pkt.chan = chan - chan_offset; if (command_timeout_ms == 0) { pkt.cycle = MAX(10, repeat_count); } else { @@ -138,10 +138,10 @@ void RCOutput::update_channel_masks() { switch (_dshot_esc_type) { case DSHOT_ESC_BLHELI: if (_reversible_mask & (1U<