mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 22:58:32 -04:00
AP_BLHeli: use native motor numbering
This commit is contained in:
parent
417a8a5147
commit
7bfb135822
@ -1466,14 +1466,7 @@ void AP_BLHeli::read_telemetry_packet(void)
|
|||||||
const uint8_t motor_idx = motor_map[last_telem_esc];
|
const uint8_t motor_idx = motor_map[last_telem_esc];
|
||||||
// we have received valid data, mark the ESC as now active
|
// we have received valid data, mark the ESC as now active
|
||||||
hal.rcout->set_active_escs_mask(1<<motor_idx);
|
hal.rcout->set_active_escs_mask(1<<motor_idx);
|
||||||
|
update_rpm(motor_idx, new_rpm);
|
||||||
uint8_t normalized_motor_idx = motor_idx - chan_offset;
|
|
||||||
#if HAL_WITH_IO_MCU
|
|
||||||
if (AP_BoardConfig::io_enabled()) {
|
|
||||||
normalized_motor_idx = motor_idx;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
update_rpm(normalized_motor_idx, new_rpm);
|
|
||||||
|
|
||||||
TelemetryData t {
|
TelemetryData t {
|
||||||
.temperature_cdeg = int16_t(buf[0] * 100),
|
.temperature_cdeg = int16_t(buf[0] * 100),
|
||||||
@ -1482,7 +1475,7 @@ void AP_BLHeli::read_telemetry_packet(void)
|
|||||||
.consumption_mah = float(uint16_t((buf[5]<<8) | buf[6])),
|
.consumption_mah = float(uint16_t((buf[5]<<8) | buf[6])),
|
||||||
};
|
};
|
||||||
|
|
||||||
update_telem_data(normalized_motor_idx, t,
|
update_telem_data(motor_idx, t,
|
||||||
AP_ESC_Telem_Backend::TelemetryType::CURRENT
|
AP_ESC_Telem_Backend::TelemetryType::CURRENT
|
||||||
| AP_ESC_Telem_Backend::TelemetryType::VOLTAGE
|
| AP_ESC_Telem_Backend::TelemetryType::VOLTAGE
|
||||||
| AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION
|
| AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION
|
||||||
|
Loading…
Reference in New Issue
Block a user