mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_OSD: use highest ESC temp rather than motor temp
This commit is contained in:
parent
0d35641399
commit
a14aee11a9
@ -488,7 +488,7 @@ void AP_OSD::update_stats()
|
|||||||
// max esc temp
|
// max esc temp
|
||||||
AP_ESC_Telem& telem = AP::esc_telem();
|
AP_ESC_Telem& telem = AP::esc_telem();
|
||||||
int16_t highest_temperature = 0;
|
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);
|
_stats.max_esc_temp = MAX(_stats.max_esc_temp, highest_temperature);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -2003,11 +2003,11 @@ void AP_OSD_Screen::draw_esc_temp(uint8_t x, uint8_t y)
|
|||||||
int16_t etemp;
|
int16_t etemp;
|
||||||
|
|
||||||
if (esc_index > 0) {
|
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;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else if (!AP::esc_telem().get_highest_motor_temperature(etemp)) {
|
else if (!AP::esc_telem().get_highest_temperature(etemp)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user