simulator: fix airspeed temperature

- HIL_SENSOR temperature is only being sent with barometer data
This commit is contained in:
Daniel Agar 2020-09-28 12:56:56 -04:00 committed by GitHub
parent 828134c56f
commit fe6a1ce882
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 5 additions and 1 deletions

View File

@ -169,6 +169,8 @@ private:
PX4Barometer _px4_baro_0{6620172}; // 6620172: DRV_BARO_DEVTYPE_BAROSIM, BUS: 1, ADDR: 4, TYPE: SIMULATION
PX4Barometer _px4_baro_1{6620428}; // 6620428: DRV_BARO_DEVTYPE_BAROSIM, BUS: 2, ADDR: 4, TYPE: SIMULATION
float _sensors_temperature{0};
perf_counter_t _perf_sim_delay{perf_alloc(PC_ELAPSED, MODULE_NAME": network delay")};
perf_counter_t _perf_sim_interval{perf_alloc(PC_INTERVAL, MODULE_NAME": network interval")};

View File

@ -224,6 +224,8 @@ void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor
_px4_mag_0.set_temperature(sensors.temperature);
_px4_mag_1.set_temperature(sensors.temperature);
_sensors_temperature = sensors.temperature;
}
}
@ -274,7 +276,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 = sensors.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;