AP_ESC_Telem: use highest ESC temp rather than motor temp

This commit is contained in:
Andy Piper 2024-08-06 19:29:41 +01:00 committed by Andrew Tridgell
parent 245119b99f
commit 153266b8db
2 changed files with 3 additions and 3 deletions

View File

@ -260,13 +260,13 @@ bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const
}
// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC
bool AP_ESC_Telem::get_highest_motor_temperature(int16_t& temp) const
bool AP_ESC_Telem::get_highest_temperature(int16_t& temp) const
{
uint8_t valid_escs = 0;
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
int16_t temp_temp;
if (get_motor_temperature(i, temp_temp)) {
if (get_temperature(i, temp_temp)) {
temp = MAX(temp, temp_temp);
valid_escs++;
}

View File

@ -53,7 +53,7 @@ public:
bool get_motor_temperature(uint8_t esc_index, int16_t& temp) const;
// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC
bool get_highest_motor_temperature(int16_t& temp) const;
bool get_highest_temperature(int16_t& temp) const;
// get an individual ESC's current in Ampere if available, returns true on success
bool get_current(uint8_t esc_index, float& amps) const;