AP_Periph: fixed temperature reporting

more common to have ESC temp than motor temp, so report ESC
temperature
This commit is contained in:
Andrew Tridgell 2021-12-17 11:37:10 +11:00
parent 7c57e1521c
commit d62e946d48

View File

@ -1561,7 +1561,7 @@ void AP_Periph_FW::esc_telem_update()
pkt.current = nan;
}
int16_t temperature;
if (esc_telem.get_motor_temperature(i, temperature)) {
if (esc_telem.get_temperature(i, temperature)) {
pkt.temperature = temperature*0.01 + C_TO_KELVIN;
} else {
pkt.temperature = nan;