AP_OSD: use highest ESC temp rather than motor temp

This commit is contained in:
Andy Piper 2024-08-06 19:29:09 +01:00 committed by Andrew Tridgell
parent 42cf3aed97
commit 102f483623
2 changed files with 3 additions and 3 deletions

View File

@ -506,7 +506,7 @@ void AP_OSD::update_stats()
// max esc temp
AP_ESC_Telem& telem = AP::esc_telem();
int16_t highest_temperature = 0;
telem.get_highest_motor_temperature(highest_temperature);
telem.get_highest_temperature(highest_temperature);
_stats.max_esc_temp = MAX(_stats.max_esc_temp, highest_temperature);
#endif
}

View File

@ -2013,11 +2013,11 @@ void AP_OSD_Screen::draw_esc_temp(uint8_t x, uint8_t y)
int16_t etemp;
if (esc_index > 0) {
if (!AP::esc_telem().get_motor_temperature(esc_index-1, etemp)) {
if (!AP::esc_telem().get_temperature(esc_index-1, etemp)) {
return;
}
}
else if (!AP::esc_telem().get_highest_motor_temperature(etemp)) {
else if (!AP::esc_telem().get_highest_temperature(etemp)) {
return;
}