Skip to content

Commit

Permalink
remove temp field from airspeed.msg, adjust temp selection
Browse files Browse the repository at this point in the history
  • Loading branch information
haumarco committed Jan 20, 2025
1 parent b09340c commit 404291d
Show file tree
Hide file tree
Showing 11 changed files with 35 additions and 34 deletions.
2 changes: 0 additions & 2 deletions msg/Airspeed.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,4 @@ float32 indicated_airspeed_m_s # indicated airspeed in m/s

float32 true_airspeed_m_s # true filtered airspeed in m/s

float32 air_temperature_celsius # air temperature in degrees Celsius, -1000 if unknown

float32 confidence # confidence value from 0 to 1 for this sensor
3 changes: 1 addition & 2 deletions msg/VehicleAirData.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,9 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint32 baro_device_id # unique device ID for the selected barometer

float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH.
float32 baro_temp_celcius # Temperature in degrees Celsius
float32 baro_pressure_pa # Absolute pressure in Pascals
float32 ambient_temperature # Abient temperature in degrees Celsius

float32 rho # air density
float32 eas2tas # equivalent airspeed to true airspeed conversion factor

uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes.
2 changes: 1 addition & 1 deletion src/drivers/telemetry/hott/messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ build_eam_response(uint8_t *buffer, size_t *size)
msg.eam_sensor_id = EAM_SENSOR_ID;
msg.sensor_text_id = EAM_SENSOR_TEXT_ID;

msg.temperature1 = (uint8_t)(airdata.baro_temp_celcius + 20);
msg.temperature1 = (uint8_t)(airdata.ambient_temperature + 20);
msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG;

msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10);
Expand Down
2 changes: 1 addition & 1 deletion src/modules/airspeed_selector/airspeed_selector_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,7 +388,7 @@ AirspeedModule::Run()
input_data.airspeed_indicated_raw = airspeed_raw.indicated_airspeed_m_s;
input_data.airspeed_true_raw = airspeed_raw.true_airspeed_m_s;
input_data.airspeed_timestamp = airspeed_raw.timestamp;
input_data.air_temperature_celsius = airspeed_raw.air_temperature_celsius;
input_data.air_temperature_celsius = _vehicle_air_data.ambient_temperature;

if (_in_takeoff_situation) {
// set flag to false if either speed is above stall speed,
Expand Down
1 change: 0 additions & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2669,7 +2669,6 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
airspeed.timestamp_sample = timestamp_sample;
airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f;
airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f;
airspeed.air_temperature_celsius = 15.f;
airspeed.timestamp = hrt_absolute_time();
_airspeed_pub.publish(airspeed);
}
Expand Down
2 changes: 1 addition & 1 deletion src/modules/mavlink/streams/HIGHRES_IMU.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ class MavlinkStreamHighresIMU : public MavlinkStream
msg.abs_pressure = air_data.baro_pressure_pa;
msg.diff_pressure = differential_pressure.differential_pressure_pa;
msg.pressure_alt = air_data.baro_alt_meter;
msg.temperature = air_data.baro_temp_celcius;
msg.temperature = air_data.ambient_temperature;
msg.fields_updated = fields_updated;

mavlink_msg_highres_imu_send_struct(_mavlink->get_channel(), &msg);
Expand Down
13 changes: 12 additions & 1 deletion src/modules/mavlink/streams/HIGH_LATENCY2.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/failsafe_flags.h>
#include <uORB/topics/health_report.h>
#include <uORB/topics/vehicle_air_data.h>

#include <px4_platform_common/events.h>

Expand Down Expand Up @@ -521,6 +522,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream
update_gps();
update_vehicle_status();
update_wind();
update_vehicle_air_data();
}

void update_airspeed()
Expand All @@ -529,7 +531,6 @@ class MavlinkStreamHighLatency2 : public MavlinkStream

if (_airspeed_sub.update(&airspeed)) {
_airspeed.add_value(airspeed.indicated_airspeed_m_s, _update_rate_filtered);
_temperature.add_value(airspeed.air_temperature_celsius, _update_rate_filtered);
}
}

Expand Down Expand Up @@ -610,6 +611,15 @@ class MavlinkStreamHighLatency2 : public MavlinkStream
}
}

void update_vehicle_air_data()
{
vehicle_air_data_s air_data;

if (_vehicle_air_data_sub.update(&air_data)) {
_temperature.add_value(air_data.ambient_temperature, _update_rate_filtered);
}
}

void set_default_values(mavlink_high_latency2_t &msg) const
{
msg.airspeed = 0;
Expand Down Expand Up @@ -659,6 +669,7 @@ class MavlinkStreamHighLatency2 : public MavlinkStream
uORB::Subscription _tecs_status_sub{ORB_ID(tecs_status)};
uORB::Subscription _wind_sub{ORB_ID(wind)};
uORB::Subscription _health_report_sub{ORB_ID(health_report)};
uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)};

SimpleAnalyzer _airspeed;
SimpleAnalyzer _airspeed_sp;
Expand Down
12 changes: 4 additions & 8 deletions src/modules/sensors/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -286,14 +286,11 @@ void Sensors::diff_pres_poll()

air_temperature_celsius = diff_pres.temperature;

} else {
} else if ((air_data.timestamp != 0) && PX4_ISFINITE(air_data.ambient_temperature)
&& (air_data.ambient_temperature >= -40.f) && (air_data.ambient_temperature <= 125.f)) {
// differential pressure temperature invalid, check barometer
if ((air_data.timestamp != 0) && PX4_ISFINITE(air_data.baro_temp_celcius)
&& (air_data.baro_temp_celcius >= -40.f) && (air_data.baro_temp_celcius <= 125.f)) {

// TODO: review PCB_TEMP_ESTIMATE_DEG, ignore for external baro
air_temperature_celsius = air_data.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG;
}
// TODO: review PCB_TEMP_ESTIMATE_DEG, ignore for external baro
air_temperature_celsius = air_data.ambient_temperature - PCB_TEMP_ESTIMATE_DEG;
}

// push raw data into validator
Expand Down Expand Up @@ -354,7 +351,6 @@ void Sensors::diff_pres_poll()
airspeed.timestamp_sample = timestamp_sample;
airspeed.indicated_airspeed_m_s = indicated_airspeed_m_s;
airspeed.true_airspeed_m_s = true_airspeed_m_s;
airspeed.air_temperature_celsius = temperature;
airspeed.confidence = _airspeed_validator.confidence(hrt_absolute_time());
airspeed.timestamp = hrt_absolute_time();
_airspeed_pub.publish(airspeed);
Expand Down
27 changes: 14 additions & 13 deletions src/modules/sensors/vehicle_air_data/VehicleAirData.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,20 +77,23 @@ void VehicleAirData::Stop()
}
}

void VehicleAirData::AirTemperatureUpdate()
void VehicleAirData::AirTemperatureUpdate(float &temperature)
{
// use the temperature from the differential pressure sensor if available
// otherwise use the temperature from the selected barometer
differential_pressure_s differential_pressure;

static constexpr float temperature_min_celsius = -20.f;
static constexpr float temperature_max_celsius = 35.f;
static constexpr float temperature_min_celsius = -40.f;
static constexpr float temperature_max_celsius = 125.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) {
if (_differential_pressure_sub.copy(&differential_pressure)
&& hrt_absolute_time() - differential_pressure.timestamp_sample < 1_s
&& PX4_ISFINITE(differential_pressure.temperature)
) {

_air_temperature_celsius = math::constrain(differential_pressure.temperature, temperature_min_celsius,
temperature_max_celsius);
temperature = math::constrain(differential_pressure.temperature, temperature_min_celsius,
temperature_max_celsius);
}
}

Expand Down Expand Up @@ -139,8 +142,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++) {
Expand Down Expand Up @@ -260,7 +261,8 @@ void VehicleAirData::Run()

if (publish) {
const float pressure_pa = _data_sum[instance] / _data_sum_count[instance];
const float temperature = _temperature_sum[instance] / _data_sum_count[instance];
float temperature = _temperature_sum[instance] / _data_sum_count[instance];
AirTemperatureUpdate(temperature);

const float pressure_sealevel_pa = _param_sens_baro_qnh.get() * 100.f;
const float altitude = getAltitudeFromPressure(pressure_pa, pressure_sealevel_pa);
Expand All @@ -273,10 +275,9 @@ void VehicleAirData::Run()
out.timestamp_sample = timestamp_sample;
out.baro_device_id = _calibration[instance].device_id();
out.baro_alt_meter = altitude;
out.baro_temp_celcius = temperature;
out.ambient_temperature = temperature;
out.baro_pressure_pa = pressure_pa;
out.rho = air_density;
out.eas2tas = sqrtf(kAirDensitySeaLevelStandardAtmos / math::max(air_density, FLT_EPSILON));
out.calibration_count = _calibration[instance].calibration_count();
out.timestamp = hrt_absolute_time();

Expand Down
4 changes: 1 addition & 3 deletions src/modules/sensors/vehicle_air_data/VehicleAirData.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class VehicleAirData : public ModuleParams, public px4::ScheduledWorkItem
private:
void Run() override;

void AirTemperatureUpdate();
void AirTemperatureUpdate(float &temperature);
void CheckFailover(const hrt_abstime &time_now_us);
bool ParametersUpdate(bool force = false);
void UpdateStatus();
Expand Down Expand Up @@ -121,8 +121,6 @@ class VehicleAirData : public ModuleParams, public px4::ScheduledWorkItem

int8_t _selected_sensor_sub_index{-1};

float _air_temperature_celsius{20.f}; // initialize with typical 20degC ambient temperature

DEFINE_PARAMETERS(
(ParamFloat<px4::params::SENS_BARO_QNH>) _param_sens_baro_qnh,
(ParamFloat<px4::params::SENS_BARO_RATE>) _param_sens_baro_rate
Expand Down
1 change: 0 additions & 1 deletion src/modules/simulation/simulator_sih/sih.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -556,7 +556,6 @@ void Sih::send_airspeed(const hrt_abstime &time_now_us)
// regardless of vehicle type, body frame, etc this holds as long as wind=0
airspeed.true_airspeed_m_s = fmaxf(0.1f, _v_E.norm() + generate_wgn() * 0.2f);
airspeed.indicated_airspeed_m_s = airspeed.true_airspeed_m_s * sqrtf(_wing_l.get_rho() / RHO);
airspeed.air_temperature_celsius = NAN;
airspeed.confidence = 0.7f;
airspeed.timestamp = hrt_absolute_time();
_airspeed_pub.publish(airspeed);
Expand Down

0 comments on commit 404291d

Please sign in to comment.