AP_HAL_ChibiOS: ensure reverse and reversible masks are applied to iomcu

This commit is contained in:
Andy Piper 2023-07-05 16:48:50 +01:00 committed by Andrew Tridgell
parent d9f42236ad
commit c6c78a9c32
2 changed files with 5 additions and 5 deletions

View File

@ -229,7 +229,7 @@ public:
* The mask uses servo channel numbering * The mask uses servo channel numbering
*/ */
void set_reversed_mask(uint32_t chanmask) override; void set_reversed_mask(uint32_t chanmask) override;
uint32_t get_reversed_mask() override { return _reversed_mask << chan_offset; } uint32_t get_reversed_mask() override { return _reversed_mask; }
/* /*
mark escs as active for the purpose of sending dshot commands mark escs as active for the purpose of sending dshot commands

View File

@ -138,14 +138,14 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman
// The chanmask passed is added (ORed) into any existing mask. // The chanmask passed is added (ORed) into any existing mask.
// The mask uses servo channel numbering // The mask uses servo channel numbering
void RCOutput::set_reversed_mask(uint32_t chanmask) { void RCOutput::set_reversed_mask(uint32_t chanmask) {
_reversed_mask |= (chanmask >> chan_offset); _reversed_mask |= chanmask;
} }
// Set the dshot outputs that should be reversible/3D // Set the dshot outputs that should be reversible/3D
// The chanmask passed is added (ORed) into any existing mask. // The chanmask passed is added (ORed) into any existing mask.
// The mask uses servo channel numbering // The mask uses servo channel numbering
void RCOutput::set_reversible_mask(uint32_t chanmask) { void RCOutput::set_reversible_mask(uint32_t chanmask) {
_reversible_mask |= (chanmask >> chan_offset); _reversible_mask |= chanmask;
} }
// Update the dshot outputs that should be reversible/3D at 1Hz // Update the dshot outputs that should be reversible/3D at 1Hz
@ -164,10 +164,10 @@ void RCOutput::update_channel_masks() {
case DSHOT_ESC_BLHELI_EDT: case DSHOT_ESC_BLHELI_EDT:
case DSHOT_ESC_BLHELI_EDT_S: case DSHOT_ESC_BLHELI_EDT_S:
if (_reversible_mask & (1U<<i)) { if (_reversible_mask & (1U<<i)) {
send_dshot_command(DSHOT_3D_ON, i + chan_offset, 0, 10, true); send_dshot_command(DSHOT_3D_ON, i, 0, 10, true);
} }
if (_reversed_mask & (1U<<i)) { if (_reversed_mask & (1U<<i)) {
send_dshot_command(DSHOT_REVERSE, i + chan_offset, 0, 10, true); send_dshot_command(DSHOT_REVERSE, i, 0, 10, true);
} }
break; break;
default: default: