AP_MSP: use highest ESC temp rather than motor temp

This commit is contained in:
Andy Piper 2024-08-06 19:30:00 +01:00 committed by Andrew Tridgell
parent 005c182e61
commit 702c76e885
1 changed files with 1 additions and 1 deletions

View File

@ -91,7 +91,7 @@ MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_esc_sensor_data(sbuf_t *dst)
int16_t highest_temperature = 0;
AP_ESC_Telem& telem = AP::esc_telem();
if (!displaying_stats_screen()) {
telem.get_highest_motor_temperature(highest_temperature);
telem.get_highest_temperature(highest_temperature);
} else {
#if OSD_ENABLED
AP_OSD *osd = AP::osd();