posix drivers: Populate baro device ID

TODO - use unique HW ID
This commit is contained in:
Paul Riseborough 2017-01-09 13:26:34 +01:00 committed by Lorenz Meier
parent 0ba31b521c
commit c21b4aaf2e
4 changed files with 12 additions and 1 deletions

View File

@ -680,6 +680,9 @@ BAROSIM::collect()
report.altitude = raw_baro.altitude;
report.temperature = raw_baro.temperature;
/* TODO get device ID for sensor */
report.device_id = 0;
/* publish it */
if (!(m_pub_blocked)) {
if (_baro_topic != nullptr) {

View File

@ -155,9 +155,11 @@ int DfBmp280Wrapper::_publish(struct baro_sensor_data &data)
baro_report.pressure = data.pressure_pa;
baro_report.temperature = data.temperature_c;
// TODO: verify this, it's just copied from the MS5611 driver.
/* TODO get device ID for sensor */
baro_report.device_id = 0;
// Constant for now
const double MSL_PRESSURE_KPA = 101325.0 / 1000.0;

View File

@ -156,6 +156,9 @@ int DfMS5607Wrapper::_publish(struct baro_sensor_data &data)
// TODO: verify this, it's just copied from the MS5611 driver.
/* TODO get device ID for sensor */
baro_report.device_id = 0;
// Constant for now
const double MSL_PRESSURE_KPA = 101325.0 / 1000.0;

View File

@ -156,6 +156,9 @@ int DfMS5611Wrapper::_publish(struct baro_sensor_data &data)
// TODO: verify this, it's just copied from the MS5611 driver.
/* TODO get device ID for sensor */
baro_report.device_id = 0;
// Constant for now
const double MSL_PRESSURE_KPA = 101325.0 / 1000.0;