From 2a83a404914e9d4211f1d2b7be8ab8aade255a29 Mon Sep 17 00:00:00 2001 From: Daniel Agar <daniel@agar.ca> Date: Sat, 3 Nov 2018 14:56:34 -0400 Subject: [PATCH] delete accel_report (alias for sensor_accel_s) --- src/drivers/drv_accel.h | 1 - src/drivers/imu/adis16448/adis16448.cpp | 14 +++++++------- src/drivers/imu/adis16477/ADIS16477.cpp | 4 ++-- src/drivers/imu/adis16477/ADIS16477_main.cpp | 2 +- src/drivers/imu/bma180/bma180.cpp | 12 ++++++------ src/drivers/imu/bmi055/BMI055_accel.cpp | 12 ++++++------ src/drivers/imu/bmi055/bmi055_main.cpp | 2 +- src/drivers/imu/bmi160/bmi160.cpp | 12 ++++++------ src/drivers/imu/bmi160/bmi160_main.cpp | 2 +- src/drivers/imu/fxos8701cq/fxos8701cq.cpp | 16 ++++++++-------- src/drivers/imu/lsm303d/lsm303d.cpp | 16 ++++++++-------- src/drivers/imu/mpu6000/mpu6000.cpp | 14 +++++++------- src/drivers/imu/mpu9250/main.cpp | 2 +- src/drivers/imu/mpu9250/mpu9250.cpp | 12 ++++++------ .../matlab_csv_serial/matlab_csv_serial.c | 4 ++-- .../commander/accelerometer_calibration.cpp | 6 +++--- src/modules/mavlink/mavlink_receiver.cpp | 4 ++-- src/modules/sensors/voted_sensors_update.cpp | 4 ++-- src/modules/simulator/accelsim/accelsim.cpp | 10 +++++----- src/modules/simulator/gyrosim/gyrosim.cpp | 14 +++++++------- src/modules/simulator/simulator_mavlink.cpp | 2 +- .../df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp | 2 +- .../qurt/fc_addon/mpu_spi/mpu9x50_main.cpp | 4 ++-- src/systemcmds/tests/test_sensors.c | 2 +- 24 files changed, 86 insertions(+), 87 deletions(-) diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h index ef19427983..0e4b3786a5 100644 --- a/src/drivers/drv_accel.h +++ b/src/drivers/drv_accel.h @@ -52,7 +52,6 @@ #define ACCEL2_DEVICE_PATH "/dev/accel2" #include <uORB/topics/sensor_accel.h> -#define accel_report sensor_accel_s /** accel scaling factors; Vout = Vscale * (Vin + Voffset) */ struct accel_calibration_s { diff --git a/src/drivers/imu/adis16448/adis16448.cpp b/src/drivers/imu/adis16448/adis16448.cpp index d2ba484f3e..b745468955 100644 --- a/src/drivers/imu/adis16448/adis16448.cpp +++ b/src/drivers/imu/adis16448/adis16448.cpp @@ -603,7 +603,7 @@ ADIS16448::init() goto out; } - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { goto out; @@ -665,7 +665,7 @@ ADIS16448::init() measure(); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -841,7 +841,7 @@ ADIS16448::_set_gyro_dyn_range(uint16_t desired_gyro_dyn_range) ssize_t ADIS16448::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(accel_report); + unsigned count = buflen / sizeof(sensor_accel_s); /* buffer must be large enough */ if (count < 1) { @@ -862,7 +862,7 @@ ADIS16448::read(struct file *filp, char *buffer, size_t buflen) perf_count(_accel_reads); /* copy reports out of our buffer to the caller */ - accel_report *arp = reinterpret_cast<accel_report *>(buffer); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int transferred = 0; while (count--) { @@ -875,7 +875,7 @@ ADIS16448::read(struct file *filp, char *buffer, size_t buflen) } /* return the number of bytes transferred */ - return (transferred * sizeof(accel_report)); + return (transferred * sizeof(sensor_accel_s)); } int @@ -1353,7 +1353,7 @@ ADIS16448::measure() /* * Report buffers. */ - accel_report arb; + sensor_accel_s arb; gyro_report grb; mag_report mrb; @@ -1750,7 +1750,7 @@ fail: void test() { - accel_report a_report; + sensor_accel_s a_report{}; gyro_report g_report; mag_report m_report; diff --git a/src/drivers/imu/adis16477/ADIS16477.cpp b/src/drivers/imu/adis16477/ADIS16477.cpp index e9ea40d3b2..5ee08c638f 100644 --- a/src/drivers/imu/adis16477/ADIS16477.cpp +++ b/src/drivers/imu/adis16477/ADIS16477.cpp @@ -200,7 +200,7 @@ ADIS16477::init() measure(); /* advertise sensor topic, measure manually to initialize valid report */ - accel_report arp = {}; + sensor_accel_s arp = {}; /* measurement will have generated a report, publish */ _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, &_accel_orb_class_instance, ORB_PRIO_MAX); @@ -593,7 +593,7 @@ ADIS16477::measure() bool ADIS16477::publish_accel(const ADISReport &report) { - accel_report arb = {}; + sensor_accel_s arb = {}; arb.timestamp = hrt_absolute_time(); arb.device_id = _device_id.devid; arb.error_count = perf_event_count(_bad_transfers); diff --git a/src/drivers/imu/adis16477/ADIS16477_main.cpp b/src/drivers/imu/adis16477/ADIS16477_main.cpp index fbcbcf159b..bb0b783bdc 100644 --- a/src/drivers/imu/adis16477/ADIS16477_main.cpp +++ b/src/drivers/imu/adis16477/ADIS16477_main.cpp @@ -113,7 +113,7 @@ fail: void test() { - accel_report a_report; + sensor_accel_s a_report{}; gyro_report g_report; ssize_t sz; diff --git a/src/drivers/imu/bma180/bma180.cpp b/src/drivers/imu/bma180/bma180.cpp index 6c01df7b2d..5b67bcb308 100644 --- a/src/drivers/imu/bma180/bma180.cpp +++ b/src/drivers/imu/bma180/bma180.cpp @@ -278,7 +278,7 @@ BMA180::init() } /* allocate basic report buffers */ - _reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_reports == nullptr) { goto out; @@ -325,7 +325,7 @@ BMA180::init() measure(); if (_class_instance == CLASS_DEVICE_PRIMARY) { - struct accel_report arp; + sensor_accel_s arp; _reports->get(&arp); /* measurement will have generated a report, publish */ @@ -352,8 +352,8 @@ BMA180::probe() ssize_t BMA180::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct accel_report); - struct accel_report *arp = reinterpret_cast<struct accel_report *>(buffer); + unsigned count = buflen / sizeof(sensor_accel_s); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int ret = 0; /* buffer must be large enough */ @@ -661,7 +661,7 @@ BMA180::measure() // } raw_report; // #pragma pack(pop) - struct accel_report report; + sensor_accel_s report; /* start the performance counter */ perf_begin(_sample_perf); @@ -796,7 +796,7 @@ void test() { int fd = -1; - struct accel_report a_report; + sensor_accel_s a_report; ssize_t sz; /* get the driver */ diff --git a/src/drivers/imu/bmi055/BMI055_accel.cpp b/src/drivers/imu/bmi055/BMI055_accel.cpp index 9fd44f464d..884e9fbd13 100644 --- a/src/drivers/imu/bmi055/BMI055_accel.cpp +++ b/src/drivers/imu/bmi055/BMI055_accel.cpp @@ -116,7 +116,7 @@ BMI055_accel::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { goto out; @@ -139,7 +139,7 @@ BMI055_accel::init() measure(); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -262,7 +262,7 @@ BMI055_accel::accel_set_sample_rate(float frequency) ssize_t BMI055_accel::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(accel_report); + unsigned count = buflen / sizeof(sensor_accel_s); /* buffer must be large enough */ if (count < 1) { @@ -281,7 +281,7 @@ BMI055_accel::read(struct file *filp, char *buffer, size_t buflen) } /* copy reports out of our buffer to the caller */ - accel_report *arp = reinterpret_cast<accel_report *>(buffer); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int transferred = 0; while (count--) { @@ -294,7 +294,7 @@ BMI055_accel::read(struct file *filp, char *buffer, size_t buflen) } /* return the number of bytes transferred */ - return (transferred * sizeof(accel_report)); + return (transferred * sizeof(sensor_accel_s)); } int @@ -671,7 +671,7 @@ BMI055_accel::measure() /* * Report buffers. */ - accel_report arb; + sensor_accel_s arb; arb.timestamp = hrt_absolute_time(); diff --git a/src/drivers/imu/bmi055/bmi055_main.cpp b/src/drivers/imu/bmi055/bmi055_main.cpp index 919bc70552..0ea9b8d5fb 100644 --- a/src/drivers/imu/bmi055/bmi055_main.cpp +++ b/src/drivers/imu/bmi055/bmi055_main.cpp @@ -225,7 +225,7 @@ test(bool external_bus, enum sensor_type sensor) { const char *path_accel = external_bus ? BMI055_DEVICE_PATH_ACCEL_EXT : BMI055_DEVICE_PATH_ACCEL; const char *path_gyro = external_bus ? BMI055_DEVICE_PATH_GYRO_EXT : BMI055_DEVICE_PATH_GYRO; - accel_report a_report; + sensor_accel_s a_report{}; gyro_report g_report; ssize_t sz; diff --git a/src/drivers/imu/bmi160/bmi160.cpp b/src/drivers/imu/bmi160/bmi160.cpp index 487ba2017a..9bb522b6c3 100644 --- a/src/drivers/imu/bmi160/bmi160.cpp +++ b/src/drivers/imu/bmi160/bmi160.cpp @@ -138,7 +138,7 @@ BMI160::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { goto out; @@ -184,7 +184,7 @@ BMI160::init() measure(); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -444,7 +444,7 @@ BMI160::_set_dlpf_filter(uint16_t bandwidth) ssize_t BMI160::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(accel_report); + unsigned count = buflen / sizeof(sensor_accel_s); /* buffer must be large enough */ if (count < 1) { @@ -465,7 +465,7 @@ BMI160::read(struct file *filp, char *buffer, size_t buflen) perf_count(_accel_reads); /* copy reports out of our buffer to the caller */ - accel_report *arp = reinterpret_cast<accel_report *>(buffer); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int transferred = 0; while (count--) { @@ -478,7 +478,7 @@ BMI160::read(struct file *filp, char *buffer, size_t buflen) } /* return the number of bytes transferred */ - return (transferred * sizeof(accel_report)); + return (transferred * sizeof(sensor_accel_s)); } int @@ -1043,7 +1043,7 @@ BMI160::measure() /* * Report buffers. */ - accel_report arb; + sensor_accel_s arb{}; gyro_report grb; /* diff --git a/src/drivers/imu/bmi160/bmi160_main.cpp b/src/drivers/imu/bmi160/bmi160_main.cpp index 04ba7fdd45..e973caa25b 100644 --- a/src/drivers/imu/bmi160/bmi160_main.cpp +++ b/src/drivers/imu/bmi160/bmi160_main.cpp @@ -121,7 +121,7 @@ test(bool external_bus) { const char *path_accel = external_bus ? BMI160_DEVICE_PATH_ACCEL_EXT : BMI160_DEVICE_PATH_ACCEL; const char *path_gyro = external_bus ? BMI160_DEVICE_PATH_GYRO_EXT : BMI160_DEVICE_PATH_GYRO; - accel_report a_report; + sensor_accel_s a_report{}; gyro_report g_report; ssize_t sz; diff --git a/src/drivers/imu/fxos8701cq/fxos8701cq.cpp b/src/drivers/imu/fxos8701cq/fxos8701cq.cpp index 652d51b520..74fd0cce3b 100644 --- a/src/drivers/imu/fxos8701cq/fxos8701cq.cpp +++ b/src/drivers/imu/fxos8701cq/fxos8701cq.cpp @@ -582,7 +582,7 @@ FXOS8701CQ::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { return ret; @@ -643,7 +643,7 @@ FXOS8701CQ::init() _accel_class_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -717,8 +717,8 @@ FXOS8701CQ::probe() ssize_t FXOS8701CQ::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct accel_report); - accel_report *arb = reinterpret_cast<accel_report *>(buffer); + unsigned count = buflen / sizeof(sensor_accel_s); + sensor_accel_s *arb = reinterpret_cast<sensor_accel_s *>(buffer); int ret = 0; /* buffer must be large enough */ @@ -1305,7 +1305,7 @@ FXOS8701CQ::measure() } raw_accel_mag_report; #pragma pack(pop) - accel_report accel_report; + sensor_accel_s accel_report; /* start the performance counter */ perf_begin(_accel_sample_perf); @@ -1761,7 +1761,7 @@ test() { int rv = 1; int fd_accel = -1; - struct accel_report accel_report; + sensor_accel_s accel_report; ssize_t sz; #if !defined(BOARD_HAS_NOISY_FXOS8700_MAG) int fd_mag = -1; @@ -1778,9 +1778,9 @@ test() } /* do a simple demand read */ - sz = read(fd_accel, &accel_report, sizeof(accel_report)); + sz = read(fd_accel, &accel_report, sizeof(sensor_accel_s)); - if (sz != sizeof(accel_report)) { + if (sz != sizeof(sensor_accel_s)) { PX4_ERR("immediate read failed"); goto exit_with_accel; } diff --git a/src/drivers/imu/lsm303d/lsm303d.cpp b/src/drivers/imu/lsm303d/lsm303d.cpp index c6462d21aa..2b891387b2 100644 --- a/src/drivers/imu/lsm303d/lsm303d.cpp +++ b/src/drivers/imu/lsm303d/lsm303d.cpp @@ -617,7 +617,7 @@ LSM303D::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { goto out; @@ -654,7 +654,7 @@ LSM303D::init() _accel_class_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -731,8 +731,8 @@ LSM303D::probe() ssize_t LSM303D::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct accel_report); - accel_report *arb = reinterpret_cast<accel_report *>(buffer); + unsigned count = buflen / sizeof(sensor_accel_s); + sensor_accel_s *arb = reinterpret_cast<sensor_accel_s *>(buffer); int ret = 0; /* buffer must be large enough */ @@ -1370,7 +1370,7 @@ LSM303D::measure() } raw_accel_report; #pragma pack(pop) - accel_report accel_report; + sensor_accel_s accel_report; /* start the performance counter */ perf_begin(_accel_sample_perf); @@ -1845,7 +1845,7 @@ void test() { int fd_accel = -1; - struct accel_report accel_report; + sensor_accel_s accel_report; ssize_t sz; int ret; @@ -1857,9 +1857,9 @@ test() } /* do a simple demand read */ - sz = read(fd_accel, &accel_report, sizeof(accel_report)); + sz = read(fd_accel, &accel_report, sizeof(sensor_accel_s)); - if (sz != sizeof(accel_report)) { + if (sz != sizeof(sensor_accel_s)) { err(1, "immediate read failed"); } diff --git a/src/drivers/imu/mpu6000/mpu6000.cpp b/src/drivers/imu/mpu6000/mpu6000.cpp index 33965eec7a..d927cb73d6 100644 --- a/src/drivers/imu/mpu6000/mpu6000.cpp +++ b/src/drivers/imu/mpu6000/mpu6000.cpp @@ -634,7 +634,7 @@ MPU6000::init() ret = -ENOMEM; /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { return ret; @@ -706,7 +706,7 @@ MPU6000::init() measure(); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -1003,7 +1003,7 @@ MPU6000::_set_icm_acc_dlpf_filter(uint16_t frequency_hz) ssize_t MPU6000::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(accel_report); + unsigned count = buflen / sizeof(sensor_accel_s); /* buffer must be large enough */ if (count < 1) { @@ -1022,7 +1022,7 @@ MPU6000::read(struct file *filp, char *buffer, size_t buflen) } /* copy reports out of our buffer to the caller */ - accel_report *arp = reinterpret_cast<accel_report *>(buffer); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int transferred = 0; while (count--) { @@ -1035,7 +1035,7 @@ MPU6000::read(struct file *filp, char *buffer, size_t buflen) } /* return the number of bytes transferred */ - return (transferred * sizeof(accel_report)); + return (transferred * sizeof(sensor_accel_s)); } int @@ -1818,7 +1818,7 @@ MPU6000::measure() /* * Report buffers. */ - accel_report arb; + sensor_accel_s arb; gyro_report grb; /* @@ -2270,7 +2270,7 @@ void test(enum MPU6000_BUS busid) { struct mpu6000_bus_option &bus = find_bus(busid); - accel_report a_report; + sensor_accel_s a_report{}; gyro_report g_report; ssize_t sz; diff --git a/src/drivers/imu/mpu9250/main.cpp b/src/drivers/imu/mpu9250/main.cpp index 1f1772905f..5471bfdd13 100644 --- a/src/drivers/imu/mpu9250/main.cpp +++ b/src/drivers/imu/mpu9250/main.cpp @@ -316,7 +316,7 @@ void test(enum MPU9250_BUS busid) { struct mpu9250_bus_option &bus = find_bus(busid); - accel_report a_report; + sensor_accel_s a_report{}; gyro_report g_report; mag_report m_report; ssize_t sz; diff --git a/src/drivers/imu/mpu9250/mpu9250.cpp b/src/drivers/imu/mpu9250/mpu9250.cpp index dfa9200e1e..87c02555ec 100644 --- a/src/drivers/imu/mpu9250/mpu9250.cpp +++ b/src/drivers/imu/mpu9250/mpu9250.cpp @@ -288,7 +288,7 @@ MPU9250::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); ret = -ENOMEM; if (_accel_reports == nullptr) { @@ -390,7 +390,7 @@ MPU9250::init() measure(); /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; + sensor_accel_s arp; _accel_reports->get(&arp); /* measurement will have generated a report, publish */ @@ -621,7 +621,7 @@ MPU9250::_set_dlpf_filter(uint16_t frequency_hz) ssize_t MPU9250::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(accel_report); + unsigned count = buflen / sizeof(sensor_accel_s); /* buffer must be large enough */ if (count < 1) { @@ -642,7 +642,7 @@ MPU9250::read(struct file *filp, char *buffer, size_t buflen) perf_count(_accel_reads); /* copy reports out of our buffer to the caller */ - accel_report *arp = reinterpret_cast<accel_report *>(buffer); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int transferred = 0; while (count--) { @@ -655,7 +655,7 @@ MPU9250::read(struct file *filp, char *buffer, size_t buflen) } /* return the number of bytes transferred */ - return (transferred * sizeof(accel_report)); + return (transferred * sizeof(sensor_accel_s)); } int @@ -1287,7 +1287,7 @@ MPU9250::measure() /* * Report buffers. */ - accel_report arb; + sensor_accel_s arb{}; gyro_report grb; /* diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c index 3bb0dcdaf3..f2f384e678 100644 --- a/src/examples/matlab_csv_serial/matlab_csv_serial.c +++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c @@ -183,8 +183,8 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) } /* subscribe to vehicle status, attitude, sensors and flow*/ - struct accel_report accel0; - struct accel_report accel1; + struct sensor_accel_s accel0; + struct sensor_accel_s accel1; struct gyro_report gyro0; struct gyro_report gyro1; diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 3751f074f3..2a65279f77 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -479,7 +479,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub for(unsigned i = 0; i < orb_accel_count && !found_cur_accel; i++) { worker_data.subs[cur_accel] = orb_subscribe_multi(ORB_ID(sensor_accel), i); - struct accel_report report = {}; + sensor_accel_s report = {}; orb_copy(ORB_ID(sensor_accel), worker_data.subs[cur_accel], &report); #ifdef __PX4_NUTTX @@ -538,7 +538,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub for (unsigned i = 0; i < max_accel_sens; i++) { if (worker_data.subs[i] >= 0) { /* figure out which sensors were active */ - struct accel_report arp = {}; + sensor_accel_s arp = {}; (void)orb_copy(ORB_ID(sensor_accel), worker_data.subs[i], &arp); if (arp.timestamp != 0 && timestamps[i] != arp.timestamp) { (*active_sensors)++; @@ -626,7 +626,7 @@ calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[m if (changed) { - struct accel_report arp; + sensor_accel_s arp; orb_copy(ORB_ID(sensor_accel), subs[s], &arp); // Apply thermal offset corrections in sensor/board frame diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 57d62a3fcd..d86b86ae68 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2068,7 +2068,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) /* accelerometer */ { - struct accel_report accel = {}; + sensor_accel_s accel = {}; accel.timestamp = timestamp; accel.x_raw = imu.xacc / (CONSTANTS_ONE_G / 1000.0f); @@ -2469,7 +2469,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) /* accelerometer */ { - struct accel_report accel = {}; + sensor_accel_s accel = {}; accel.timestamp = timestamp; accel.x_raw = hil_state.xacc / CONSTANTS_ONE_G * 1e3f; diff --git a/src/modules/sensors/voted_sensors_update.cpp b/src/modules/sensors/voted_sensors_update.cpp index 44e736180a..bb06a28f34 100644 --- a/src/modules/sensors/voted_sensors_update.cpp +++ b/src/modules/sensors/voted_sensors_update.cpp @@ -179,7 +179,7 @@ void VotedSensorsUpdate::parameters_update() if (topic_instance < _accel.subscription_count) { // valid subscription, so get the driver id by getting the published sensor data - struct accel_report report; + sensor_accel_s report; if (orb_copy(ORB_ID(sensor_accel), _accel.subscription[topic_instance], &report) == 0) { int temp = _temperature_compensation.set_sensor_id_accel(report.device_id, topic_instance); @@ -545,7 +545,7 @@ void VotedSensorsUpdate::accel_poll(struct sensor_combined_s &raw) orb_check(_accel.subscription[uorb_index], &accel_updated); if (accel_updated) { - struct accel_report accel_report; + sensor_accel_s accel_report; int ret = orb_copy(ORB_ID(sensor_accel), _accel.subscription[uorb_index], &accel_report); diff --git a/src/modules/simulator/accelsim/accelsim.cpp b/src/modules/simulator/accelsim/accelsim.cpp index a25c84cf43..9e6a76e978 100644 --- a/src/modules/simulator/accelsim/accelsim.cpp +++ b/src/modules/simulator/accelsim/accelsim.cpp @@ -321,7 +321,7 @@ ACCELSIM::init() int ret = -1; struct mag_report mrp = {}; - struct accel_report arp = {}; + sensor_accel_s arp = {}; /* do SIM init first */ if (VirtDevObj::init() != 0) { @@ -330,7 +330,7 @@ ACCELSIM::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { goto out; @@ -410,8 +410,8 @@ ACCELSIM::transfer(uint8_t *send, uint8_t *recv, unsigned len) ssize_t ACCELSIM::devRead(void *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct accel_report); - accel_report *arb = reinterpret_cast<accel_report *>(buffer); + unsigned count = buflen / sizeof(sensor_accel_s); + sensor_accel_s *arb = reinterpret_cast<sensor_accel_s *>(buffer); int ret = 0; /* buffer must be large enough */ @@ -781,7 +781,7 @@ ACCELSIM::_measure() } raw_accel_report; #pragma pack(pop) - accel_report accel_report = {}; + sensor_accel_s accel_report = {}; /* start the performance counter */ perf_begin(_accel_sample_perf); diff --git a/src/modules/simulator/gyrosim/gyrosim.cpp b/src/modules/simulator/gyrosim/gyrosim.cpp index 0d6ca6df9b..4db24f4868 100644 --- a/src/modules/simulator/gyrosim/gyrosim.cpp +++ b/src/modules/simulator/gyrosim/gyrosim.cpp @@ -363,7 +363,7 @@ GYROSIM::init() PX4_DEBUG("init"); int ret = 1; - struct accel_report arp = {}; + sensor_accel_s arp = {}; struct gyro_report grp = {}; @@ -376,7 +376,7 @@ GYROSIM::init() } /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report)); + _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); if (_accel_reports == nullptr) { PX4_WARN("_accel_reports creation failed"); @@ -536,7 +536,7 @@ GYROSIM::_set_sample_rate(unsigned desired_sample_rate_hz) ssize_t GYROSIM::devRead(void *buffer, size_t buflen) { - unsigned count = buflen / sizeof(accel_report); + unsigned count = buflen / sizeof(sensor_accel_s); /* buffer must be large enough */ if (count < 1) { @@ -557,7 +557,7 @@ GYROSIM::devRead(void *buffer, size_t buflen) perf_count(_accel_reads); /* copy reports out of our buffer to the caller */ - accel_report *arp = reinterpret_cast<accel_report *>(buffer); + sensor_accel_s *arp = reinterpret_cast<sensor_accel_s *>(buffer); int transferred = 0; while (count--) { @@ -570,7 +570,7 @@ GYROSIM::devRead(void *buffer, size_t buflen) } /* return the number of bytes transferred */ - return (transferred * sizeof(accel_report)); + return (transferred * sizeof(sensor_accel_s)); } int @@ -893,7 +893,7 @@ GYROSIM::_measure() /* * Report buffers. */ - accel_report arb = {}; + sensor_accel_s arb = {}; gyro_report grb = {}; // for now use local time but this should be the timestamp of the simulator @@ -1175,7 +1175,7 @@ test() { const char *path_accel = MPU_DEVICE_PATH_ACCEL; const char *path_gyro = MPU_DEVICE_PATH_GYRO; - accel_report a_report; + sensor_accel_s a_report; gyro_report g_report; ssize_t sz; diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index d8efe0ea25..54f3881fb1 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -1025,7 +1025,7 @@ int Simulator::publish_sensor_topics(mavlink_hil_sensor_t *imu) /* accelerometer */ { - struct accel_report accel = {}; + sensor_accel_s accel = {}; accel.timestamp = timestamp; accel.x_raw = imu->xacc / (CONSTANTS_ONE_G / 1000.0f); diff --git a/src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp b/src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp index c11dba6995..cf0868f855 100644 --- a/src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp +++ b/src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp @@ -239,7 +239,7 @@ DfLsm9ds1Wrapper::~DfLsm9ds1Wrapper() int DfLsm9ds1Wrapper::start() { // TODO: don't publish garbage here - accel_report accel_report = {}; + sensor_accel_s accel_report = {}; _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &accel_report, &_accel_orb_class_instance, ORB_PRIO_DEFAULT); diff --git a/src/platforms/qurt/fc_addon/mpu_spi/mpu9x50_main.cpp b/src/platforms/qurt/fc_addon/mpu_spi/mpu9x50_main.cpp index 804c0e1a30..84c9fbb15d 100644 --- a/src/platforms/qurt/fc_addon/mpu_spi/mpu9x50_main.cpp +++ b/src/platforms/qurt/fc_addon/mpu_spi/mpu9x50_main.cpp @@ -97,7 +97,7 @@ static orb_advert_t _mag_pub = nullptr; /**< compass data publication */ static int _mag_orb_class_instance; /**< instance handle for mag devices */ static int _params_sub; /**< parameter update subscription */ static struct gyro_report _gyro; /**< gyro report */ -static struct accel_report _accel; /**< accel report */ +static sensor_accel_s _accel; /**< accel report */ static struct mag_report _mag; /**< mag report */ static struct gyro_calibration_s _gyro_sc; /**< gyro scale */ static struct accel_calibration_s _accel_sc; /**< accel scale */ @@ -368,7 +368,7 @@ bool create_pubs() { // initialize the reports memset(&_gyro, 0, sizeof(struct gyro_report)); - memset(&_accel, 0, sizeof(struct accel_report)); + memset(&_accel, 0, sizeof(sensor_accel_s)); memset(&_mag, 0, sizeof(struct mag_report)); _gyro_pub = orb_advertise_multi(ORB_ID(sensor_gyro), &_gyro, diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c index 37faa39318..70dc512482 100644 --- a/src/systemcmds/tests/test_sensors.c +++ b/src/systemcmds/tests/test_sensors.c @@ -90,7 +90,7 @@ accel(int argc, char *argv[], const char *path) fflush(stdout); int fd; - struct accel_report buf; + struct sensor_accel_s buf; int ret; fd = px4_open(path, O_RDONLY); -- GitLab