AP_HAL_ChibiOS: correct channel offsets for dshot commands

Co-authored-by: Randy Mackay <rmackay9@yahoo.com>
This commit is contained in:
Andy Piper 2022-03-22 14:54:47 +00:00 committed by Andrew Tridgell
parent 43beccd86c
commit bafe46882f
2 changed files with 4 additions and 4 deletions

View File

@ -200,7 +200,7 @@ public:
* The mask uses servo channel numbering * The mask uses servo channel numbering
*/ */
void set_reversed_mask(uint16_t chanmask) override; 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 mark escs as active for the purpose of sending dshot commands

View File

@ -98,7 +98,7 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman
DshotCommandPacket pkt; DshotCommandPacket pkt;
pkt.command = command; pkt.command = command;
pkt.chan = chan + chan_offset; pkt.chan = chan - chan_offset;
if (command_timeout_ms == 0) { if (command_timeout_ms == 0) {
pkt.cycle = MAX(10, repeat_count); pkt.cycle = MAX(10, repeat_count);
} else { } else {
@ -138,10 +138,10 @@ void RCOutput::update_channel_masks() {
switch (_dshot_esc_type) { switch (_dshot_esc_type) {
case DSHOT_ESC_BLHELI: case DSHOT_ESC_BLHELI:
if (_reversible_mask & (1U<<i)) { if (_reversible_mask & (1U<<i)) {
send_dshot_command(DSHOT_3D_ON, i, 0, 10, true); send_dshot_command(DSHOT_3D_ON, i + chan_offset, 0, 10, true);
} }
if (_reversed_mask & (1U<<i)) { if (_reversed_mask & (1U<<i)) {
send_dshot_command(DSHOT_REVERSE, i, 0, 10, true); send_dshot_command(DSHOT_REVERSE, i + chan_offset, 0, 10, true);
} }
break; break;
default: default: