From e98ea6fd912848a2a9d1180aeb13b50365dd7be1 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 1 Oct 2024 09:05:06 +0200 Subject: [PATCH] VehicleAirData: remove unused air temperature handling Signed-off-by: Silvan Fuhrer --- .../vehicle_air_data/VehicleAirData.cpp | 19 ------------------- .../vehicle_air_data/VehicleAirData.hpp | 7 ------- 2 files changed, 26 deletions(-) diff --git a/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp b/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp index 819eac6c2d..042db825bb 100644 --- a/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp +++ b/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp @@ -78,23 +78,6 @@ void VehicleAirData::Stop() } } -void VehicleAirData::AirTemperatureUpdate() -{ - differential_pressure_s differential_pressure; - - static constexpr float temperature_min_celsius = -20.f; - static constexpr float temperature_max_celsius = 35.f; - - // update air temperature if data from differential pressure sensor is finite and not exactly 0 - // limit the range to max 35°C to limt the error due to heated up airspeed sensors prior flight - if (_differential_pressure_sub.update(&differential_pressure) && PX4_ISFINITE(differential_pressure.temperature) - && fabsf(differential_pressure.temperature) > FLT_EPSILON) { - - _air_temperature_celsius = math::constrain(differential_pressure.temperature, temperature_min_celsius, - temperature_max_celsius); - } -} - bool VehicleAirData::ParametersUpdate(bool force) { // Check if parameters have changed @@ -140,8 +123,6 @@ void VehicleAirData::Run() const bool parameter_update = ParametersUpdate(); - AirTemperatureUpdate(); - bool updated[MAX_SENSOR_COUNT] {}; for (int uorb_index = 0; uorb_index < MAX_SENSOR_COUNT; uorb_index++) { diff --git a/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp b/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp index fd28de34f8..13d5f116cc 100644 --- a/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp +++ b/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp @@ -49,7 +49,6 @@ #include #include #include -#include #include #include #include @@ -73,8 +72,6 @@ public: private: void Run() override; - - void AirTemperatureUpdate(); void CheckFailover(const hrt_abstime &time_now_us); bool ParametersUpdate(bool force = false); void UpdateStatus(); @@ -87,8 +84,6 @@ private: uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; - uORB::Subscription _differential_pressure_sub{ORB_ID(differential_pressure)}; - uORB::SubscriptionCallbackWorkItem _sensor_sub[MAX_SENSOR_COUNT] { {this, ORB_ID(sensor_baro), 0}, {this, ORB_ID(sensor_baro), 1}, @@ -121,8 +116,6 @@ private: int8_t _selected_sensor_sub_index{-1}; - float _air_temperature_celsius{20.f}; // initialize with typical 20degC ambient temperature - DEFINE_PARAMETERS( (ParamFloat) _param_sens_baro_qnh, (ParamFloat) _param_sens_baro_rate