AP_DroneCAN: populate ESC power percentage

This commit is contained in:
Iampete1 2024-02-02 13:34:01 +00:00 committed by Peter Hall
parent a974f3fd42
commit 8ec3d0f0a9
1 changed files with 8 additions and 1 deletions

View File

@ -1447,14 +1447,21 @@ void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavc
.temperature_cdeg = int16_t((KELVIN_TO_C(msg.temperature)) * 100),
.voltage = msg.voltage,
.current = msg.current,
#if AP_EXTENDED_ESC_TELEM_ENABLED
.power_percentage = msg.power_rating_pct,
#endif
};
update_rpm(esc_index, msg.rpm, msg.error_count);
update_telem_data(esc_index, t,
(isnan(msg.current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT)
| (isnan(msg.voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)
| (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE));
| (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE)
#if AP_EXTENDED_ESC_TELEM_ENABLED
| AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE
#endif
);
#endif // HAL_WITH_ESC_TELEM
}
#if AP_EXTENDED_ESC_TELEM_ENABLED