diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 5ca7e94996..636648ca97 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -212,21 +212,18 @@ void Simulator::send_controls() void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor_t &sensors) { - float temperature = NAN; - // temperature only updated with baro if ((sensors.fields_updated & SensorSource::BARO) == SensorSource::BARO) { if (PX4_ISFINITE(sensors.temperature)) { - temperature = sensors.temperature; - _px4_accel_0.set_temperature(temperature); - _px4_accel_1.set_temperature(temperature); + _px4_accel_0.set_temperature(sensors.temperature); + _px4_accel_1.set_temperature(sensors.temperature); - _px4_gyro_0.set_temperature(temperature); - _px4_gyro_1.set_temperature(temperature); + _px4_gyro_0.set_temperature(sensors.temperature); + _px4_gyro_1.set_temperature(sensors.temperature); - _px4_mag_0.set_temperature(temperature); - _px4_mag_1.set_temperature(temperature); + _px4_mag_0.set_temperature(sensors.temperature); + _px4_mag_1.set_temperature(sensors.temperature); } } @@ -261,15 +258,15 @@ void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor if ((sensors.fields_updated & SensorSource::BARO) == SensorSource::BARO && !_baro_blocked) { if (_baro_stuck) { _px4_baro_0.update(time, _px4_baro_0.get().pressure); - _px4_baro_0.set_temperature(time, _px4_baro_0.get().temperature); + _px4_baro_0.set_temperature(_px4_baro_0.get().temperature); _px4_baro_1.update(time, _px4_baro_1.get().pressure); - _px4_baro_1.set_temperature(time, _px4_baro_1.get().temperature); + _px4_baro_1.set_temperature(_px4_baro_1.get().temperature); } else { _px4_baro_0.update(time, sensors.abs_pressure); - _px4_baro_0.set_temperature(temperature); + _px4_baro_0.set_temperature(sensors.temperature); _px4_baro_1.update(time, sensors.abs_pressure); - _px4_baro_1.set_temperature(temperature); + _px4_baro_1.set_temperature(sensors.temperature); } } @@ -277,7 +274,7 @@ void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor if ((sensors.fields_updated & SensorSource::DIFF_PRESS) == SensorSource::DIFF_PRESS && !_airspeed_blocked) { differential_pressure_s report{}; report.timestamp = time; - report.temperature = temperature; + report.temperature = sensors.temperature; report.differential_pressure_filtered_pa = sensors.diff_pressure * 100.0f; // convert from millibar to bar; report.differential_pressure_raw_pa = sensors.diff_pressure * 100.0f; // convert from millibar to bar;