Skip to content

Commit

Permalink
delete baro_report (alias for sensor_baro_s)
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar authored and LorenzMeier committed Nov 5, 2018
1 parent 85c2b63 commit 571364c
Show file tree
Hide file tree
Showing 16 changed files with 38 additions and 39 deletions.
12 changes: 6 additions & 6 deletions src/drivers/barometer/bmp280/bmp280.cpp
Expand Up @@ -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");
Expand Down Expand Up @@ -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()) {
Expand Down Expand Up @@ -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<struct baro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_baro_s);
sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
int ret = 0;

/* buffer must be large enough */
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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;

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/lps22hb/LPS22HB.cpp
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/lps22hb/LPS22HB.hpp
Expand Up @@ -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.
Expand Down
10 changes: 5 additions & 5 deletions src/drivers/barometer/lps25h/lps25h.cpp
Expand Up @@ -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<struct baro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_baro_s);
sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
int ret = 0;

/* buffer must be large enough */
Expand Down Expand Up @@ -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);

Expand Down Expand Up @@ -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 */
Expand Down Expand Up @@ -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;

Expand Down
10 changes: 5 additions & 5 deletions src/drivers/barometer/mpl3115a2/mpl3115a2.cpp
Expand Up @@ -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) {
Expand Down Expand Up @@ -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<struct baro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_baro_s);
sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
int ret = 0;

/* buffer must be large enough */
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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;

Expand Down
10 changes: 5 additions & 5 deletions src/drivers/barometer/ms5611/ms5611.cpp
Expand Up @@ -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();
Expand Down Expand Up @@ -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<struct baro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_baro_s);
sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
int ret = 0;

/* buffer must be large enough */
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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;

Expand Down
1 change: 0 additions & 1 deletion src/drivers/drv_baro.h
Expand Up @@ -51,6 +51,5 @@
#define BARO0_DEVICE_PATH "/dev/baro0"

#include <uORB/topics/sensor_baro.h>
#define baro_report sensor_baro_s

#endif /* _DRV_BARO_H */
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions src/modules/sensors/voted_sensors_update.cpp
Expand Up @@ -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);
Expand Down Expand Up @@ -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);

Expand Down
6 changes: 3 additions & 3 deletions src/modules/simulator/barosim/baro.cpp
Expand Up @@ -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;
Expand Down Expand Up @@ -162,7 +162,7 @@ int
BAROSIM::init()
{
int ret;
struct baro_report brp = {};
sensor_baro_s brp = {};

ret = VirtDevObj::init();

Expand All @@ -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");
Expand Down
2 changes: 1 addition & 1 deletion src/modules/simulator/simulator_mavlink.cpp
Expand Up @@ -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;
Expand Down
8 changes: 4 additions & 4 deletions src/modules/uavcan/sensors/baro.cpp
Expand Up @@ -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()
Expand Down Expand Up @@ -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<struct baro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_baro_s);
sensor_baro_s *baro_buf = reinterpret_cast<sensor_baro_s *>(buffer);
int ret = 0;

/* buffer must be large enough */
Expand Down Expand Up @@ -136,7 +136,7 @@ void UavcanBarometerBridge::air_temperature_sub_cb(const
void UavcanBarometerBridge::air_pressure_sub_cb(const
uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticPressure> &msg)
{
baro_report report;
sensor_baro_s report{};

/*
* FIXME HACK
Expand Down
Expand Up @@ -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;

Expand Down
Expand Up @@ -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
Expand Down
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/systemcmds/tests/test_sensors.c
Expand Up @@ -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);
Expand Down

0 comments on commit 571364c

Please sign in to comment.