From 571364c61760c66c30d03036ae8b908c80eafa5e Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 3 Nov 2018 15:25:59 -0400 Subject: [PATCH] delete baro_report (alias for sensor_baro_s) --- src/drivers/barometer/bmp280/bmp280.cpp | 12 ++++++------ src/drivers/barometer/lps22hb/LPS22HB.cpp | 2 +- src/drivers/barometer/lps22hb/LPS22HB.hpp | 2 +- src/drivers/barometer/lps25h/lps25h.cpp | 10 +++++----- src/drivers/barometer/mpl3115a2/mpl3115a2.cpp | 10 +++++----- src/drivers/barometer/ms5611/ms5611.cpp | 10 +++++----- src/drivers/drv_baro.h | 1 - src/modules/mavlink/mavlink_receiver.cpp | 2 +- src/modules/sensors/voted_sensors_update.cpp | 4 ++-- src/modules/simulator/barosim/baro.cpp | 6 +++--- src/modules/simulator/simulator_mavlink.cpp | 2 +- src/modules/uavcan/sensors/baro.cpp | 8 ++++---- .../drivers/df_bmp280_wrapper/df_bmp280_wrapper.cpp | 2 +- .../drivers/df_ms5607_wrapper/df_ms5607_wrapper.cpp | 2 +- .../drivers/df_ms5611_wrapper/df_ms5611_wrapper.cpp | 2 +- src/systemcmds/tests/test_sensors.c | 2 +- 16 files changed, 38 insertions(+), 39 deletions(-) diff --git a/src/drivers/barometer/bmp280/bmp280.cpp b/src/drivers/barometer/bmp280/bmp280.cpp index b7a8197b4962..2ceab70e7cbb 100644 --- a/src/drivers/barometer/bmp280/bmp280.cpp +++ b/src/drivers/barometer/bmp280/bmp280.cpp @@ -202,7 +202,7 @@ BMP280::init() } /* allocate basic report buffers */ - _reports = new ringbuffer::RingBuffer(2, sizeof(baro_report)); + _reports = new ringbuffer::RingBuffer(2, sizeof(sensor_baro_s)); if (_reports == nullptr) { PX4_ERR("can't get memory for reports"); @@ -249,7 +249,7 @@ BMP280::init() _fcal.p9 = _cal->p9 * powf(2, -35); /* do a first measurement cycle to populate reports with valid data */ - struct baro_report brp; + sensor_baro_s brp; _reports->flush(); if (measure()) { @@ -279,8 +279,8 @@ BMP280::init() ssize_t BMP280::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct baro_report); - struct baro_report *brp = reinterpret_cast(buffer); + unsigned count = buflen / sizeof(sensor_baro_s); + sensor_baro_s *brp = reinterpret_cast(buffer); int ret = 0; /* buffer must be large enough */ @@ -497,7 +497,7 @@ BMP280::collect() perf_begin(_sample_perf); - struct baro_report report; + sensor_baro_s report; /* this should be fairly close to the end of the conversion, so the best approximation of the time */ report.timestamp = hrt_absolute_time(); report.error_count = perf_event_count(_comms_errors); @@ -715,7 +715,7 @@ void test(enum BMP280_BUS busid) { struct bmp280_bus_option &bus = find_bus(busid); - struct baro_report report; + sensor_baro_s report; ssize_t sz; int ret; diff --git a/src/drivers/barometer/lps22hb/LPS22HB.cpp b/src/drivers/barometer/lps22hb/LPS22HB.cpp index fea8326b3c96..b49cefe8a7c8 100644 --- a/src/drivers/barometer/lps22hb/LPS22HB.cpp +++ b/src/drivers/barometer/lps22hb/LPS22HB.cpp @@ -279,7 +279,7 @@ int LPS22HB::collect() { perf_begin(_sample_perf); - struct baro_report new_report; + sensor_baro_s new_report; /* get measurements from the device : MSB enables register address auto-increment */ #pragma pack(push, 1) diff --git a/src/drivers/barometer/lps22hb/LPS22HB.hpp b/src/drivers/barometer/lps22hb/LPS22HB.hpp index b51bccdc3c7f..559fa564bd36 100644 --- a/src/drivers/barometer/lps22hb/LPS22HB.hpp +++ b/src/drivers/barometer/lps22hb/LPS22HB.hpp @@ -115,7 +115,7 @@ class LPS22HB : public cdev::CDev perf_counter_t _sample_perf; perf_counter_t _comms_errors; - baro_report _last_report{}; /**< used for info() */ + sensor_baro_s _last_report{}; /**< used for info() */ /** * Initialise the automatic measurement state machine and start it. diff --git a/src/drivers/barometer/lps25h/lps25h.cpp b/src/drivers/barometer/lps25h/lps25h.cpp index ac7dd18b25dd..d6983f49100d 100644 --- a/src/drivers/barometer/lps25h/lps25h.cpp +++ b/src/drivers/barometer/lps25h/lps25h.cpp @@ -376,8 +376,8 @@ LPS25H::init() ssize_t LPS25H::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct baro_report); - struct baro_report *brp = reinterpret_cast(buffer); + unsigned count = buflen / sizeof(sensor_baro_s); + sensor_baro_s *brp = reinterpret_cast(buffer); int ret = 0; /* buffer must be large enough */ @@ -425,7 +425,7 @@ LPS25H::read(struct file *filp, char *buffer, size_t buflen) } if (_reports->get(brp)) { - ret = sizeof(struct baro_report); + ret = sizeof(sensor_baro_s); } } while (0); @@ -658,7 +658,7 @@ LPS25H::collect() int ret; perf_begin(_sample_perf); - struct baro_report new_report; + sensor_baro_s new_report; bool sensor_is_onboard = false; /* this should be fairly close to the end of the measurement, so the best approximation of the time */ @@ -889,7 +889,7 @@ void test(enum LPS25H_BUS busid) { struct lps25h_bus_option &bus = find_bus(busid); - struct baro_report report; + sensor_baro_s report; ssize_t sz; int ret; diff --git a/src/drivers/barometer/mpl3115a2/mpl3115a2.cpp b/src/drivers/barometer/mpl3115a2/mpl3115a2.cpp index 0300e6a39737..e935c49531f6 100644 --- a/src/drivers/barometer/mpl3115a2/mpl3115a2.cpp +++ b/src/drivers/barometer/mpl3115a2/mpl3115a2.cpp @@ -263,7 +263,7 @@ MPL3115A2::init() /* register alternate interfaces if we have to */ _class_instance = register_class_devname(BARO_BASE_DEVICE_PATH); - struct baro_report brp; + sensor_baro_s brp; _reports->flush(); while (true) { @@ -323,8 +323,8 @@ MPL3115A2::init() ssize_t MPL3115A2::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct baro_report); - struct baro_report *brp = reinterpret_cast(buffer); + unsigned count = buflen / sizeof(sensor_baro_s); + sensor_baro_s *brp = reinterpret_cast(buffer); int ret = 0; /* buffer must be large enough */ @@ -619,7 +619,7 @@ MPL3115A2::collect() return -EAGAIN; } - struct baro_report report; + sensor_baro_s report; /* this should be fairly close to the end of the conversion, so the best approximation of the time */ report.timestamp = hrt_absolute_time(); @@ -820,7 +820,7 @@ void test(enum MPL3115A2_BUS busid) { struct mpl3115a2_bus_option &bus = find_bus(busid); - struct baro_report report; + sensor_baro_s report; ssize_t sz; int ret; diff --git a/src/drivers/barometer/ms5611/ms5611.cpp b/src/drivers/barometer/ms5611/ms5611.cpp index 9c0e156107e2..64f8f67cdb52 100644 --- a/src/drivers/barometer/ms5611/ms5611.cpp +++ b/src/drivers/barometer/ms5611/ms5611.cpp @@ -295,7 +295,7 @@ MS5611::init() /* register alternate interfaces if we have to */ _class_instance = register_class_devname(BARO_BASE_DEVICE_PATH); - struct baro_report brp; + sensor_baro_s brp; /* do a first measurement cycle to populate reports with valid data */ _measure_phase = 0; _reports->flush(); @@ -390,8 +390,8 @@ MS5611::init() ssize_t MS5611::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct baro_report); - struct baro_report *brp = reinterpret_cast(buffer); + unsigned count = buflen / sizeof(sensor_baro_s); + sensor_baro_s *brp = reinterpret_cast(buffer); int ret = 0; /* buffer must be large enough */ @@ -698,7 +698,7 @@ MS5611::collect() perf_begin(_sample_perf); - struct baro_report report; + sensor_baro_s report; /* this should be fairly close to the end of the conversion, so the best approximation of the time */ report.timestamp = hrt_absolute_time(); report.error_count = perf_event_count(_comms_errors); @@ -1023,7 +1023,7 @@ void test(enum MS5611_BUS busid) { struct ms5611_bus_option &bus = find_bus(busid); - struct baro_report report; + sensor_baro_s report; ssize_t sz; int ret; diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h index 2e5bf7ff1517..a98cda055b33 100644 --- a/src/drivers/drv_baro.h +++ b/src/drivers/drv_baro.h @@ -51,6 +51,5 @@ #define BARO0_DEVICE_PATH "/dev/baro0" #include -#define baro_report sensor_baro_s #endif /* _DRV_BARO_H */ diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 8ef7ad725a0c..b062aa9f08a9 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2110,7 +2110,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) /* baro */ { - struct baro_report baro = {}; + sensor_baro_s baro = {}; baro.timestamp = timestamp; baro.pressure = imu.abs_pressure; diff --git a/src/modules/sensors/voted_sensors_update.cpp b/src/modules/sensors/voted_sensors_update.cpp index a214ae8af9fd..64f635f00e97 100644 --- a/src/modules/sensors/voted_sensors_update.cpp +++ b/src/modules/sensors/voted_sensors_update.cpp @@ -202,7 +202,7 @@ void VotedSensorsUpdate::parameters_update() if (topic_instance < _baro.subscription_count) { // valid subscription, so get the driver id by getting the published sensor data - struct baro_report report; + sensor_baro_s report; if (orb_copy(ORB_ID(sensor_baro), _baro.subscription[topic_instance], &report) == 0) { int temp = _temperature_compensation.set_sensor_id_baro(report.device_id, topic_instance); @@ -813,7 +813,7 @@ void VotedSensorsUpdate::baro_poll(vehicle_air_data_s &airdata) orb_check(_baro.subscription[uorb_index], &baro_updated); if (baro_updated) { - struct baro_report baro_report; + sensor_baro_s baro_report; int ret = orb_copy(ORB_ID(sensor_baro), _baro.subscription[uorb_index], &baro_report); diff --git a/src/modules/simulator/barosim/baro.cpp b/src/modules/simulator/barosim/baro.cpp index 1576d05fefb4..7af81b18bbd1 100644 --- a/src/modules/simulator/barosim/baro.cpp +++ b/src/modules/simulator/barosim/baro.cpp @@ -99,7 +99,7 @@ class BAROSIM : public VirtDevObj ringbuffer::RingBuffer *_reports; /* last report */ - struct baro_report report; + sensor_baro_s report; orb_advert_t _baro_topic; int _orb_class_instance; @@ -162,7 +162,7 @@ int BAROSIM::init() { int ret; - struct baro_report brp = {}; + sensor_baro_s brp = {}; ret = VirtDevObj::init(); @@ -172,7 +172,7 @@ BAROSIM::init() } /* allocate basic report buffers */ - _reports = new ringbuffer::RingBuffer(2, sizeof(baro_report)); + _reports = new ringbuffer::RingBuffer(2, sizeof(sensor_baro_s)); if (_reports == nullptr) { PX4_ERR("can't get memory for reports"); diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index fb3fbdfa439d..d860fd57eba3 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -1061,7 +1061,7 @@ int Simulator::publish_sensor_topics(mavlink_hil_sensor_t *imu) /* baro */ { - struct baro_report baro = {}; + sensor_baro_s baro = {}; baro.timestamp = timestamp; baro.pressure = imu->abs_pressure; diff --git a/src/modules/uavcan/sensors/baro.cpp b/src/modules/uavcan/sensors/baro.cpp index 1333d8b52679..79c812d63c9e 100644 --- a/src/modules/uavcan/sensors/baro.cpp +++ b/src/modules/uavcan/sensors/baro.cpp @@ -45,7 +45,7 @@ UavcanBarometerBridge::UavcanBarometerBridge(uavcan::INode &node) : UavcanCDevSensorBridgeBase("uavcan_baro", "/dev/uavcan/baro", BARO_BASE_DEVICE_PATH, ORB_ID(sensor_baro)), _sub_air_pressure_data(node), _sub_air_temperature_data(node), - _reports(2, sizeof(baro_report)) + _reports(2, sizeof(sensor_baro_s)) { } int UavcanBarometerBridge::init() @@ -75,8 +75,8 @@ int UavcanBarometerBridge::init() ssize_t UavcanBarometerBridge::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct baro_report); - struct baro_report *baro_buf = reinterpret_cast(buffer); + unsigned count = buflen / sizeof(sensor_baro_s); + sensor_baro_s *baro_buf = reinterpret_cast(buffer); int ret = 0; /* buffer must be large enough */ @@ -136,7 +136,7 @@ void UavcanBarometerBridge::air_temperature_sub_cb(const void UavcanBarometerBridge::air_pressure_sub_cb(const uavcan::ReceivedDataStructure &msg) { - baro_report report; + sensor_baro_s report{}; /* * FIXME HACK diff --git a/src/platforms/posix/drivers/df_bmp280_wrapper/df_bmp280_wrapper.cpp b/src/platforms/posix/drivers/df_bmp280_wrapper/df_bmp280_wrapper.cpp index dbb84a257a5a..5cc75bbfce61 100644 --- a/src/platforms/posix/drivers/df_bmp280_wrapper/df_bmp280_wrapper.cpp +++ b/src/platforms/posix/drivers/df_bmp280_wrapper/df_bmp280_wrapper.cpp @@ -155,7 +155,7 @@ int DfBmp280Wrapper::_publish(struct baro_sensor_data &data) { perf_begin(_baro_sample_perf); - baro_report baro_report = {}; + sensor_baro_s baro_report = {}; baro_report.timestamp = hrt_absolute_time(); baro_report.error_count = data.error_counter; diff --git a/src/platforms/posix/drivers/df_ms5607_wrapper/df_ms5607_wrapper.cpp b/src/platforms/posix/drivers/df_ms5607_wrapper/df_ms5607_wrapper.cpp index ecac4f3597f8..a232c9152181 100644 --- a/src/platforms/posix/drivers/df_ms5607_wrapper/df_ms5607_wrapper.cpp +++ b/src/platforms/posix/drivers/df_ms5607_wrapper/df_ms5607_wrapper.cpp @@ -148,7 +148,7 @@ int DfMS5607Wrapper::_publish(struct baro_sensor_data &data) { perf_begin(_baro_sample_perf); - baro_report baro_report; + sensor_baro_s baro_report{}; baro_report.timestamp = hrt_absolute_time(); baro_report.pressure = data.pressure_pa / 100.0f; // convert to mbar diff --git a/src/platforms/posix/drivers/df_ms5611_wrapper/df_ms5611_wrapper.cpp b/src/platforms/posix/drivers/df_ms5611_wrapper/df_ms5611_wrapper.cpp index e131f21b9f45..f66a67d8d966 100644 --- a/src/platforms/posix/drivers/df_ms5611_wrapper/df_ms5611_wrapper.cpp +++ b/src/platforms/posix/drivers/df_ms5611_wrapper/df_ms5611_wrapper.cpp @@ -148,7 +148,7 @@ int DfMS5611Wrapper::_publish(struct baro_sensor_data &data) { perf_begin(_baro_sample_perf); - baro_report baro_report; + sensor_baro_s baro_report{}; baro_report.timestamp = hrt_absolute_time(); baro_report.pressure = data.pressure_pa / 100.0f; // convert to mbar diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c index 81fcbc16325c..41c2fef1d86a 100644 --- a/src/systemcmds/tests/test_sensors.c +++ b/src/systemcmds/tests/test_sensors.c @@ -230,7 +230,7 @@ baro(int argc, char *argv[], const char *path) fflush(stdout); int fd; - struct baro_report buf; + struct sensor_baro_s buf; int ret; fd = px4_open(path, O_RDONLY);