AP_BLHeli: pass motor mask to serial_setup_output()

This commit is contained in:
Andrew Tridgell 2018-08-04 18:30:22 +10:00
parent 126333c3b5
commit 65df9ace57
2 changed files with 4 additions and 2 deletions

View File

@ -515,7 +515,7 @@ bool AP_BLHeli::BL_SendBuf(const uint8_t *buf, uint16_t len)
if (blheli.chan >= num_motors) { if (blheli.chan >= num_motors) {
return false; return false;
} }
if (!hal.rcout->serial_setup_output(motor_map[blheli.chan], 19200)) { if (!hal.rcout->serial_setup_output(motor_map[blheli.chan], 19200, motor_mask)) {
blheli.ack = ACK_D_GENERAL_ERROR; blheli.ack = ACK_D_GENERAL_ERROR;
return false; return false;
} }
@ -1115,7 +1115,7 @@ void AP_BLHeli::run_connection_test(uint8_t chan)
{ {
debug_uart = hal.console; debug_uart = hal.console;
uint8_t saved_chan = blheli.chan; uint8_t saved_chan = blheli.chan;
if (blheli.buf[0] >= num_motors) { if (chan >= num_motors) {
debug("bad channel %u", chan); debug("bad channel %u", chan);
return; return;
} }
@ -1256,6 +1256,7 @@ void AP_BLHeli::update(void)
num_motors++; num_motors++;
} }
} }
motor_mask = mask;
debug("ESC: %u motors mask=0x%04x", num_motors, mask); debug("ESC: %u motors mask=0x%04x", num_motors, mask);
if (telem_rate > 0) { if (telem_rate > 0) {

View File

@ -237,6 +237,7 @@ private:
// mapping from BLHeli motor numbers to RC output channels // mapping from BLHeli motor numbers to RC output channels
uint8_t motor_map[max_motors]; uint8_t motor_map[max_motors];
uint16_t motor_mask;
// when did we last request telemetry? // when did we last request telemetry?
uint32_t last_telem_request_us; uint32_t last_telem_request_us;