From 9a3fed02637afd571c1bec6982e931518b16f508 Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Thu, 30 Sep 2021 03:24:00 -0400 Subject: [PATCH] Plane: move high_latency_air_temperature up --- ArduPlane/GCS_Mavlink.cpp | 12 ------------ ArduPlane/GCS_Mavlink.h | 1 - 2 files changed, 13 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4f4d3311fa..638c061148 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1404,18 +1404,6 @@ uint8_t GCS_MAVLINK_Plane::high_latency_wind_direction() const // need to convert -180->180 to 0->360/2 return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2; } - -int8_t GCS_MAVLINK_Plane::high_latency_air_temperature() const -{ - // return units are degC - AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); - float air_temperature; - if (airspeed != nullptr && airspeed->enabled() && airspeed->get_temperature(air_temperature)) { - return air_temperature; - } - - return INT8_MIN; -} #endif // HAL_HIGH_LATENCY2_ENABLED MAV_VTOL_STATE GCS_MAVLINK_Plane::vtol_state() const diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 23d833c11b..95fa3bca64 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -69,7 +69,6 @@ private: uint8_t high_latency_tgt_airspeed() const override; uint8_t high_latency_wind_speed() const override; uint8_t high_latency_wind_direction() const override; - int8_t high_latency_air_temperature() const override; #endif // HAL_HIGH_LATENCY2_ENABLED MAV_VTOL_STATE vtol_state() const override;