Add baro temperature to sensor voter observation (#9411)

When determining the confidence of a barometer sensor, we should
consider the temperature as well, alongside the pressure.
Low-noise baros can show the same pressure reading for a second
or two when not moving and in an indoor location.
This commit is contained in:
alessandro
2018-05-04 18:40:10 +02:00
committed by Daniel Agar
parent 6b94ef1a03
commit 3ed093ba59

View File

@@ -831,7 +831,7 @@ void VotedSensorsUpdate::baro_poll(vehicle_air_data_s &airdata)
_baro_device_id[uorb_index] = baro_report.device_id;
got_update = true;
matrix::Vector3f vect(baro_report.pressure, 0.f, 0.f);
matrix::Vector3f vect(baro_report.pressure, baro_report.temperature, 0.f);
_last_airdata[uorb_index].timestamp = baro_report.timestamp;
_last_airdata[uorb_index].baro_temp_celcius = baro_report.temperature;