Browse Source

delete gyro_report (alias for sensor_gyro_s)

sbg
Daniel Agar 6 years ago committed by Lorenz Meier
parent
commit
acc24da0c2
  1. 1
      src/drivers/drv_gyro.h
  2. 14
      src/drivers/imu/adis16448/adis16448.cpp
  3. 4
      src/drivers/imu/adis16477/ADIS16477.cpp
  4. 2
      src/drivers/imu/adis16477/ADIS16477_main.cpp
  5. 12
      src/drivers/imu/bmi055/BMI055_gyro.cpp
  6. 2
      src/drivers/imu/bmi055/bmi055_main.cpp
  7. 12
      src/drivers/imu/bmi160/bmi160.cpp
  8. 2
      src/drivers/imu/bmi160/bmi160_main.cpp
  9. 12
      src/drivers/imu/fxas21002c/fxas21002c.cpp
  10. 12
      src/drivers/imu/l3gd20/l3gd20.cpp
  11. 14
      src/drivers/imu/mpu6000/mpu6000.cpp
  12. 2
      src/drivers/imu/mpu9250/main.cpp
  13. 12
      src/drivers/imu/mpu9250/mpu9250.cpp
  14. 4
      src/examples/matlab_csv_serial/matlab_csv_serial.c
  15. 6
      src/modules/commander/gyro_calibration.cpp
  16. 2
      src/modules/commander/mag_calibration.cpp
  17. 2
      src/modules/mavlink/mavlink_receiver.cpp
  18. 4
      src/modules/sensors/voted_sensors_update.cpp
  19. 14
      src/modules/simulator/gyrosim/gyrosim.cpp
  20. 2
      src/modules/simulator/simulator_mavlink.cpp
  21. 6
      src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp
  22. 4
      src/platforms/posix/drivers/df_mpu6050_wrapper/df_mpu6050_wrapper.cpp
  23. 8
      src/platforms/posix/drivers/df_mpu9250_wrapper/df_mpu9250_wrapper.cpp
  24. 4
      src/platforms/qurt/fc_addon/mpu_spi/mpu9x50_main.cpp
  25. 2
      src/systemcmds/tests/test_sensors.c

1
src/drivers/drv_gyro.h

@ -49,7 +49,6 @@ @@ -49,7 +49,6 @@
#define GYRO_BASE_DEVICE_PATH "/dev/gyro"
#include <uORB/topics/sensor_gyro.h>
#define gyro_report sensor_gyro_s
/** gyro scaling factors; Vout = (Vin * Vscale) + Voffset */
struct gyro_calibration_s {

14
src/drivers/imu/adis16448/adis16448.cpp

@ -597,7 +597,7 @@ ADIS16448::init() @@ -597,7 +597,7 @@ ADIS16448::init()
}
/* allocate basic report buffers */
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_gyro_reports == nullptr) {
goto out;
@ -676,7 +676,7 @@ ADIS16448::init() @@ -676,7 +676,7 @@ ADIS16448::init()
warnx("ADVERT FAIL");
}
struct gyro_report grp;
sensor_gyro_s grp;
_gyro_reports->get(&grp);
@ -892,7 +892,7 @@ ADIS16448::self_test() @@ -892,7 +892,7 @@ ADIS16448::self_test()
ssize_t
ADIS16448::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
unsigned count = buflen / sizeof(sensor_gyro_s);
/* buffer must be large enough */
if (count < 1) {
@ -913,7 +913,7 @@ ADIS16448::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -913,7 +913,7 @@ ADIS16448::gyro_read(struct file *filp, char *buffer, size_t buflen)
perf_count(_gyro_reads);
/* copy reports out of our buffer to the caller */
gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
sensor_gyro_s *grp = reinterpret_cast<sensor_gyro_s *>(buffer);
int transferred = 0;
while (count--) {
@ -926,7 +926,7 @@ ADIS16448::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -926,7 +926,7 @@ ADIS16448::gyro_read(struct file *filp, char *buffer, size_t buflen)
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
return (transferred * sizeof(sensor_gyro_s));
}
ssize_t
@ -1332,7 +1332,7 @@ ADIS16448::measure() @@ -1332,7 +1332,7 @@ ADIS16448::measure()
* Report buffers.
*/
sensor_accel_s arb;
gyro_report grb;
sensor_gyro_s grb;
mag_report mrb;
grb.timestamp = arb.timestamp = mrb.timestamp = hrt_absolute_time();
@ -1729,7 +1729,7 @@ void @@ -1729,7 +1729,7 @@ void
test()
{
sensor_accel_s a_report{};
gyro_report g_report;
sensor_gyro_s g_report{};
mag_report m_report;
ssize_t sz;

4
src/drivers/imu/adis16477/ADIS16477.cpp

@ -209,7 +209,7 @@ ADIS16477::init() @@ -209,7 +209,7 @@ ADIS16477::init()
PX4_ERR("ADVERT FAIL");
}
gyro_report grp = {};
sensor_gyro_s grp = {};
_gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp, &_gyro->_gyro_orb_class_instance, ORB_PRIO_MAX);
if (_gyro->_gyro_topic == nullptr) {
@ -622,7 +622,7 @@ ADIS16477::publish_accel(const ADISReport &report) @@ -622,7 +622,7 @@ ADIS16477::publish_accel(const ADISReport &report)
bool
ADIS16477::publish_gyro(const ADISReport &report)
{
gyro_report grb = {};
sensor_gyro_s grb = {};
grb.timestamp = hrt_absolute_time();
grb.device_id = _gyro->_device_id.devid;
grb.error_count = perf_event_count(_bad_transfers);

2
src/drivers/imu/adis16477/ADIS16477_main.cpp

@ -114,7 +114,7 @@ void @@ -114,7 +114,7 @@ void
test()
{
sensor_accel_s a_report{};
gyro_report g_report;
sensor_gyro_s g_report{};
ssize_t sz;

12
src/drivers/imu/bmi055/BMI055_gyro.cpp

@ -114,7 +114,7 @@ BMI055_gyro::init() @@ -114,7 +114,7 @@ BMI055_gyro::init()
}
/* allocate basic report buffers */
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_gyro_reports == nullptr) {
goto out;
@ -144,7 +144,7 @@ BMI055_gyro::init() @@ -144,7 +144,7 @@ BMI055_gyro::init()
measure();
/* advertise sensor topic, measure manually to initialize valid report */
struct gyro_report grp;
sensor_gyro_s grp;
_gyro_reports->get(&grp);
_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp,
@ -270,7 +270,7 @@ BMI055_gyro::test_error() @@ -270,7 +270,7 @@ BMI055_gyro::test_error()
ssize_t
BMI055_gyro::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
unsigned count = buflen / sizeof(sensor_gyro_s);
/* buffer must be large enough */
if (count < 1) {
@ -289,7 +289,7 @@ BMI055_gyro::read(struct file *filp, char *buffer, size_t buflen) @@ -289,7 +289,7 @@ BMI055_gyro::read(struct file *filp, char *buffer, size_t buflen)
}
/* copy reports out of our buffer to the caller */
gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
sensor_gyro_s *grp = reinterpret_cast<sensor_gyro_s *>(buffer);
int transferred = 0;
while (count--) {
@ -302,7 +302,7 @@ BMI055_gyro::read(struct file *filp, char *buffer, size_t buflen) @@ -302,7 +302,7 @@ BMI055_gyro::read(struct file *filp, char *buffer, size_t buflen)
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
return (transferred * sizeof(sensor_gyro_s));
}
int
@ -624,7 +624,7 @@ BMI055_gyro::measure() @@ -624,7 +624,7 @@ BMI055_gyro::measure()
/*
* Report buffers.
*/
gyro_report grb;
sensor_gyro_s grb;
grb.timestamp = hrt_absolute_time();

2
src/drivers/imu/bmi055/bmi055_main.cpp

@ -226,7 +226,7 @@ test(bool external_bus, enum sensor_type sensor) @@ -226,7 +226,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;
sensor_accel_s a_report{};
gyro_report g_report;
sensor_gyro_s g_report{};
ssize_t sz;
if (sensor == BMI055_ACCEL) {

12
src/drivers/imu/bmi160/bmi160.cpp

@ -144,7 +144,7 @@ BMI160::init() @@ -144,7 +144,7 @@ BMI160::init()
goto out;
}
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_gyro_reports == nullptr) {
goto out;
@ -197,7 +197,7 @@ BMI160::init() @@ -197,7 +197,7 @@ BMI160::init()
/* advertise sensor topic, measure manually to initialize valid report */
struct gyro_report grp;
sensor_gyro_s grp;
_gyro_reports->get(&grp);
_gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp,
@ -506,7 +506,7 @@ BMI160::test_error() @@ -506,7 +506,7 @@ BMI160::test_error()
ssize_t
BMI160::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
unsigned count = buflen / sizeof(sensor_gyro_s);
/* buffer must be large enough */
if (count < 1) {
@ -527,7 +527,7 @@ BMI160::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -527,7 +527,7 @@ BMI160::gyro_read(struct file *filp, char *buffer, size_t buflen)
perf_count(_gyro_reads);
/* copy reports out of our buffer to the caller */
gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
sensor_gyro_s *grp = reinterpret_cast<sensor_gyro_s *>(buffer);
int transferred = 0;
while (count--) {
@ -540,7 +540,7 @@ BMI160::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -540,7 +540,7 @@ BMI160::gyro_read(struct file *filp, char *buffer, size_t buflen)
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
return (transferred * sizeof(sensor_gyro_s));
}
@ -1027,7 +1027,7 @@ BMI160::measure() @@ -1027,7 +1027,7 @@ BMI160::measure()
* Report buffers.
*/
sensor_accel_s arb{};
gyro_report grb;
sensor_gyro_s grb{};
/*
* Adjust and scale results to m/s^2.

2
src/drivers/imu/bmi160/bmi160_main.cpp

@ -122,7 +122,7 @@ test(bool external_bus) @@ -122,7 +122,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;
sensor_accel_s a_report{};
gyro_report g_report;
sensor_gyro_s g_report{};
ssize_t sz;
/* get the driver */

12
src/drivers/imu/fxas21002c/fxas21002c.cpp

@ -527,7 +527,7 @@ FXAS21002C::init() @@ -527,7 +527,7 @@ FXAS21002C::init()
}
/* allocate basic report buffers */
_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_reports == nullptr) {
return PX4_ERROR;
@ -541,7 +541,7 @@ FXAS21002C::init() @@ -541,7 +541,7 @@ FXAS21002C::init()
_class_instance = register_class_devname(GYRO_BASE_DEVICE_PATH);
/* advertise sensor topic, measure manually to initialize valid report */
struct gyro_report grp;
sensor_gyro_s grp;
_reports->get(&grp);
/* measurement will have generated a report, publish */
@ -608,8 +608,8 @@ FXAS21002C::probe() @@ -608,8 +608,8 @@ FXAS21002C::probe()
ssize_t
FXAS21002C::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct gyro_report);
struct gyro_report *gbuf = reinterpret_cast<struct gyro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_gyro_s);
sensor_gyro_s *gbuf = reinterpret_cast<sensor_gyro_s *>(buffer);
int ret = 0;
/* buffer must be large enough */
@ -1042,7 +1042,7 @@ FXAS21002C::measure() @@ -1042,7 +1042,7 @@ FXAS21002C::measure()
} raw_gyro_report;
#pragma pack(pop)
struct gyro_report gyro_report;
sensor_gyro_s gyro_report;
/* start the performance counter */
perf_begin(_sample_perf);
@ -1310,7 +1310,7 @@ void @@ -1310,7 +1310,7 @@ void
test()
{
int fd_gyro = -1;
struct gyro_report g_report;
sensor_gyro_s g_report{};
ssize_t sz;
/* get the driver */

12
src/drivers/imu/l3gd20/l3gd20.cpp

@ -463,7 +463,7 @@ L3GD20::init() @@ -463,7 +463,7 @@ L3GD20::init()
}
/* allocate basic report buffers */
_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_reports == nullptr) {
goto out;
@ -476,7 +476,7 @@ L3GD20::init() @@ -476,7 +476,7 @@ L3GD20::init()
measure();
/* advertise sensor topic, measure manually to initialize valid report */
struct gyro_report grp;
sensor_gyro_s grp;
_reports->get(&grp);
_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp,
@ -528,8 +528,8 @@ L3GD20::probe() @@ -528,8 +528,8 @@ L3GD20::probe()
ssize_t
L3GD20::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct gyro_report);
struct gyro_report *gbuf = reinterpret_cast<struct gyro_report *>(buffer);
unsigned count = buflen / sizeof(sensor_gyro_s);
sensor_gyro_s *gbuf = reinterpret_cast<sensor_gyro_s *>(buffer);
int ret = 0;
/* buffer must be large enough */
@ -926,7 +926,7 @@ L3GD20::measure() @@ -926,7 +926,7 @@ L3GD20::measure()
} raw_report;
#pragma pack(pop)
gyro_report report;
sensor_gyro_s report;
/* start the performance counter */
perf_begin(_sample_perf);
@ -1201,7 +1201,7 @@ void @@ -1201,7 +1201,7 @@ void
test()
{
int fd_gyro = -1;
struct gyro_report g_report;
sensor_gyro_s g_report;
ssize_t sz;
/* get the driver */

14
src/drivers/imu/mpu6000/mpu6000.cpp

@ -640,7 +640,7 @@ MPU6000::init() @@ -640,7 +640,7 @@ MPU6000::init()
return ret;
}
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_gyro_reports == nullptr) {
return ret;
@ -718,7 +718,7 @@ MPU6000::init() @@ -718,7 +718,7 @@ MPU6000::init()
}
/* advertise sensor topic, measure manually to initialize valid report */
struct gyro_report grp;
sensor_gyro_s grp;
_gyro_reports->get(&grp);
_gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp,
@ -1220,7 +1220,7 @@ MPU6000::test_error() @@ -1220,7 +1220,7 @@ MPU6000::test_error()
ssize_t
MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
unsigned count = buflen / sizeof(sensor_gyro_s);
/* buffer must be large enough */
if (count < 1) {
@ -1239,7 +1239,7 @@ MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -1239,7 +1239,7 @@ MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
}
/* copy reports out of our buffer to the caller */
gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
sensor_gyro_s *grp = reinterpret_cast<sensor_gyro_s *>(buffer);
int transferred = 0;
while (count--) {
@ -1252,7 +1252,7 @@ MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -1252,7 +1252,7 @@ MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
return (transferred * sizeof(sensor_gyro_s));
}
int
@ -1796,7 +1796,7 @@ MPU6000::measure() @@ -1796,7 +1796,7 @@ MPU6000::measure()
* Report buffers.
*/
sensor_accel_s arb;
gyro_report grb;
sensor_gyro_s grb;
/*
* Adjust and scale results to m/s^2.
@ -2248,7 +2248,7 @@ test(enum MPU6000_BUS busid) @@ -2248,7 +2248,7 @@ test(enum MPU6000_BUS busid)
{
struct mpu6000_bus_option &bus = find_bus(busid);
sensor_accel_s a_report{};
gyro_report g_report;
sensor_gyro_s g_report{};
ssize_t sz;
/* get the driver */

2
src/drivers/imu/mpu9250/main.cpp

@ -317,7 +317,7 @@ test(enum MPU9250_BUS busid) @@ -317,7 +317,7 @@ test(enum MPU9250_BUS busid)
{
struct mpu9250_bus_option &bus = find_bus(busid);
sensor_accel_s a_report{};
gyro_report g_report;
sensor_gyro_s g_report{};
mag_report m_report;
ssize_t sz;

12
src/drivers/imu/mpu9250/mpu9250.cpp

@ -295,7 +295,7 @@ MPU9250::init() @@ -295,7 +295,7 @@ MPU9250::init()
return ret;
}
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_gyro_reports == nullptr) {
return ret;
@ -403,7 +403,7 @@ MPU9250::init() @@ -403,7 +403,7 @@ MPU9250::init()
}
/* advertise sensor topic, measure manually to initialize valid report */
struct gyro_report grp;
sensor_gyro_s grp;
_gyro_reports->get(&grp);
_gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp,
@ -686,7 +686,7 @@ MPU9250::test_error() @@ -686,7 +686,7 @@ MPU9250::test_error()
ssize_t
MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
unsigned count = buflen / sizeof(sensor_gyro_s);
/* buffer must be large enough */
if (count < 1) {
@ -707,7 +707,7 @@ MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -707,7 +707,7 @@ MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen)
perf_count(_gyro_reads);
/* copy reports out of our buffer to the caller */
gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
sensor_gyro_s *grp = reinterpret_cast<sensor_gyro_s *>(buffer);
int transferred = 0;
while (count--) {
@ -720,7 +720,7 @@ MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -720,7 +720,7 @@ MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen)
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
return (transferred * sizeof(sensor_gyro_s));
}
int
@ -1265,7 +1265,7 @@ MPU9250::measure() @@ -1265,7 +1265,7 @@ MPU9250::measure()
* Report buffers.
*/
sensor_accel_s arb{};
gyro_report grb;
sensor_gyro_s grb{};
/*
* Adjust and scale results to m/s^2.

4
src/examples/matlab_csv_serial/matlab_csv_serial.c

@ -185,8 +185,8 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) @@ -185,8 +185,8 @@ int matlab_csv_serial_thread_main(int argc, char *argv[])
/* subscribe to vehicle status, attitude, sensors and flow*/
struct sensor_accel_s accel0;
struct sensor_accel_s accel1;
struct gyro_report gyro0;
struct gyro_report gyro1;
struct sensor_gyro_s gyro0;
struct sensor_gyro_s gyro1;
/* subscribe to parameter changes */
int accel0_sub = orb_subscribe_multi(ORB_ID(sensor_accel), 0);

6
src/modules/commander/gyro_calibration.cpp

@ -71,7 +71,7 @@ typedef struct { @@ -71,7 +71,7 @@ typedef struct {
int gyro_sensor_sub[max_gyros];
int sensor_correction_sub;
struct gyro_calibration_s gyro_scale[max_gyros];
struct gyro_report gyro_report_0;
sensor_gyro_s gyro_report_0;
} gyro_worker_data_t;
static calibrate_return gyro_calibration_worker(int cancel_sub, void* data)
@ -79,7 +79,7 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void* data) @@ -79,7 +79,7 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void* data)
gyro_worker_data_t* worker_data = (gyro_worker_data_t*)(data);
unsigned calibration_counter[max_gyros] = { 0 }, slow_count = 0;
const unsigned calibration_count = 5000;
struct gyro_report gyro_report;
sensor_gyro_s gyro_report;
unsigned poll_errcount = 0;
struct sensor_correction_s sensor_correction; /**< sensor thermal corrections */
@ -307,7 +307,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) @@ -307,7 +307,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
for(unsigned i = 0; i < orb_gyro_count && !found_cur_gyro; i++) {
worker_data.gyro_sensor_sub[cur_gyro] = orb_subscribe_multi(ORB_ID(sensor_gyro), i);
struct gyro_report report;
sensor_gyro_s report{};
orb_copy(ORB_ID(sensor_gyro), worker_data.gyro_sensor_sub[cur_gyro], &report);
#ifdef __PX4_NUTTX

2
src/modules/commander/mag_calibration.cpp

@ -396,7 +396,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta @@ -396,7 +396,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta
int poll_ret = px4_poll(fds, fd_count, 1000);
if (poll_ret > 0) {
struct gyro_report gyro;
sensor_gyro_s gyro{};
orb_copy(ORB_ID(sensor_gyro), sub_gyro, &gyro);
/* ensure we have a valid first timestamp */

2
src/modules/mavlink/mavlink_receiver.cpp

@ -2047,7 +2047,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) @@ -2047,7 +2047,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
/* gyro */
{
struct gyro_report gyro = {};
sensor_gyro_s gyro = {};
gyro.timestamp = timestamp;
gyro.x_raw = imu.xgyro * 1000.0f;

4
src/modules/sensors/voted_sensors_update.cpp

@ -155,7 +155,7 @@ void VotedSensorsUpdate::parameters_update() @@ -155,7 +155,7 @@ void VotedSensorsUpdate::parameters_update()
if (topic_instance < _gyro.subscription_count) {
// valid subscription, so get the driver id by getting the published sensor data
struct gyro_report report;
sensor_gyro_s report;
if (orb_copy(ORB_ID(sensor_gyro), _gyro.subscription[topic_instance], &report) == 0) {
int temp = _temperature_compensation.set_sensor_id_gyro(report.device_id, topic_instance);
@ -652,7 +652,7 @@ void VotedSensorsUpdate::gyro_poll(struct sensor_combined_s &raw) @@ -652,7 +652,7 @@ void VotedSensorsUpdate::gyro_poll(struct sensor_combined_s &raw)
orb_check(_gyro.subscription[uorb_index], &gyro_updated);
if (gyro_updated) {
struct gyro_report gyro_report;
sensor_gyro_s gyro_report;
int ret = orb_copy(ORB_ID(sensor_gyro), _gyro.subscription[uorb_index], &gyro_report);

14
src/modules/simulator/gyrosim/gyrosim.cpp

@ -363,7 +363,7 @@ GYROSIM::init() @@ -363,7 +363,7 @@ GYROSIM::init()
sensor_accel_s arp = {};
struct gyro_report grp = {};
sensor_gyro_s grp = {};
ret = VirtDevObj::init();
@ -381,7 +381,7 @@ GYROSIM::init() @@ -381,7 +381,7 @@ GYROSIM::init()
goto out;
}
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s));
if (_gyro_reports == nullptr) {
PX4_WARN("_gyro_reports creation failed");
@ -584,7 +584,7 @@ GYROSIM::self_test() @@ -584,7 +584,7 @@ GYROSIM::self_test()
ssize_t
GYROSIM::gyro_read(void *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
unsigned count = buflen / sizeof(sensor_gyro_s);
/* buffer must be large enough */
if (count < 1) {
@ -605,7 +605,7 @@ GYROSIM::gyro_read(void *buffer, size_t buflen) @@ -605,7 +605,7 @@ GYROSIM::gyro_read(void *buffer, size_t buflen)
perf_count(_gyro_reads);
/* copy reports out of our buffer to the caller */
gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
sensor_gyro_s *grp = reinterpret_cast<sensor_gyro_s *>(buffer);
int transferred = 0;
while (count--) {
@ -618,7 +618,7 @@ GYROSIM::gyro_read(void *buffer, size_t buflen) @@ -618,7 +618,7 @@ GYROSIM::gyro_read(void *buffer, size_t buflen)
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
return (transferred * sizeof(sensor_gyro_s));
}
int
@ -869,7 +869,7 @@ GYROSIM::_measure() @@ -869,7 +869,7 @@ GYROSIM::_measure()
* Report buffers.
*/
sensor_accel_s arb = {};
gyro_report grb = {};
sensor_gyro_s grb = {};
// for now use local time but this should be the timestamp of the simulator
grb.timestamp = hrt_absolute_time();
@ -1151,7 +1151,7 @@ test() @@ -1151,7 +1151,7 @@ test()
const char *path_accel = MPU_DEVICE_PATH_ACCEL;
const char *path_gyro = MPU_DEVICE_PATH_GYRO;
sensor_accel_s a_report;
gyro_report g_report;
sensor_gyro_s g_report;
ssize_t sz;
/* get the driver */

2
src/modules/simulator/simulator_mavlink.cpp

@ -1007,7 +1007,7 @@ int Simulator::publish_sensor_topics(mavlink_hil_sensor_t *imu) @@ -1007,7 +1007,7 @@ int Simulator::publish_sensor_topics(mavlink_hil_sensor_t *imu)
*/
/* gyro */
{
struct gyro_report gyro = {};
sensor_gyro_s gyro = {};
gyro.timestamp = timestamp;
gyro.x_raw = imu->xgyro * 1000.0f;

6
src/platforms/posix/drivers/df_lsm9ds1_wrapper/df_lsm9ds1_wrapper.cpp

@ -249,7 +249,7 @@ int DfLsm9ds1Wrapper::start() @@ -249,7 +249,7 @@ int DfLsm9ds1Wrapper::start()
}
// TODO: don't publish garbage here
gyro_report gyro_report = {};
sensor_gyro_s gyro_report = {};
_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &gyro_report,
&_gyro_orb_class_instance, ORB_PRIO_DEFAULT);
@ -618,8 +618,8 @@ int DfLsm9ds1Wrapper::_publish(struct imu_sensor_data &data) @@ -618,8 +618,8 @@ int DfLsm9ds1Wrapper::_publish(struct imu_sensor_data &data)
perf_begin(_publish_perf);
accel_report accel_report = {};
gyro_report gyro_report = {};
sensor_accel_s accel_report = {};
sensor_gyro_s gyro_report = {};
mag_report mag_report = {};
accel_report.timestamp = gyro_report.timestamp = hrt_absolute_time();

4
src/platforms/posix/drivers/df_mpu6050_wrapper/df_mpu6050_wrapper.cpp

@ -488,8 +488,8 @@ int DfMPU6050Wrapper::_publish(struct imu_sensor_data &data) @@ -488,8 +488,8 @@ int DfMPU6050Wrapper::_publish(struct imu_sensor_data &data)
perf_begin(_publish_perf);
accel_report accel_report = {};
gyro_report gyro_report = {};
sensor_accel_s accel_report = {};
sensor_gyro_s gyro_report = {};
accel_report.timestamp = gyro_report.timestamp = hrt_absolute_time();

8
src/platforms/posix/drivers/df_mpu9250_wrapper/df_mpu9250_wrapper.cpp

@ -285,7 +285,7 @@ DfMpu9250Wrapper::~DfMpu9250Wrapper() @@ -285,7 +285,7 @@ DfMpu9250Wrapper::~DfMpu9250Wrapper()
int DfMpu9250Wrapper::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);
@ -295,7 +295,7 @@ int DfMpu9250Wrapper::start() @@ -295,7 +295,7 @@ int DfMpu9250Wrapper::start()
}
// TODO: don't publish garbage here
gyro_report gyro_report = {};
sensor_gyro_s gyro_report = {};
_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &gyro_report,
&_gyro_orb_class_instance, ORB_PRIO_DEFAULT);
@ -612,8 +612,8 @@ int DfMpu9250Wrapper::_publish(struct imu_sensor_data &data) @@ -612,8 +612,8 @@ int DfMpu9250Wrapper::_publish(struct imu_sensor_data &data)
_update_mag_calibration();
}
accel_report accel_report = {};
gyro_report gyro_report = {};
sensor_accel_s accel_report = {};
sensor_gyro_s gyro_report = {};
mag_report mag_report = {};
accel_report.timestamp = gyro_report.timestamp = hrt_absolute_time();

4
src/platforms/qurt/fc_addon/mpu_spi/mpu9x50_main.cpp

@ -96,7 +96,7 @@ static int _accel_orb_class_instance; /**< instance handle for accel devi @@ -96,7 +96,7 @@ static int _accel_orb_class_instance; /**< instance handle for accel devi
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 sensor_gyro_s _gyro; /**< gyro report */
static sensor_accel_s _accel; /**< accel report */
static struct mag_report _mag; /**< mag report */
static struct gyro_calibration_s _gyro_sc; /**< gyro scale */
@ -367,7 +367,7 @@ void parameters_init() @@ -367,7 +367,7 @@ void parameters_init()
bool create_pubs()
{
// initialize the reports
memset(&_gyro, 0, sizeof(struct gyro_report));
memset(&_gyro, 0, sizeof(sensor_gyro_s));
memset(&_accel, 0, sizeof(sensor_accel_s));
memset(&_mag, 0, sizeof(struct mag_report));

2
src/systemcmds/tests/test_sensors.c

@ -140,7 +140,7 @@ gyro(int argc, char *argv[], const char *path) @@ -140,7 +140,7 @@ gyro(int argc, char *argv[], const char *path)
fflush(stdout);
int fd;
struct gyro_report buf;
struct sensor_gyro_s buf;
int ret;
fd = px4_open(path, O_RDONLY);

Loading…
Cancel
Save