Skip to content

Commit

Permalink
accel and gyro calibration move to msg/
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Jun 8, 2018
1 parent a62a71f commit 544a1a3
Show file tree
Hide file tree
Showing 44 changed files with 380 additions and 302 deletions.
2 changes: 2 additions & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ set(msg_files
airspeed.msg
att_pos_mocap.msg
battery_status.msg
calibration_accel.msg
calibration_gyro.msg
camera_capture.msg
camera_trigger.msg
collision_report.msg
Expand Down
10 changes: 10 additions & 0 deletions msg/calibration_accel.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@

# scaling factors; Vout = (Vin * Vscale) + Voffset

float32 x_offset
float32 y_offset
float32 z_offset

float32 x_scale
float32 y_scale
float32 z_scale
10 changes: 10 additions & 0 deletions msg/calibration_gyro.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@

# scaling factors; Vout = (Vin * Vscale) + Voffset

float32 x_offset
float32 y_offset
float32 z_offset

float32 x_scale
float32 y_scale
float32 z_scale
4 changes: 2 additions & 2 deletions msg/tools/px_generate_uorb_topic_helper.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@
'uint16': '%u',
'uint32': '%" PRIu32 "',
'uint64': '%" PRIu64 "',
'float32': '%.3f',
'float64': '%.3f',
'float32': '%.5f',
'float64': '%.6f',
'bool': '%u',
'char': '%c',
}
Expand Down
12 changes: 0 additions & 12 deletions src/drivers/drv_accel.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,18 +51,6 @@
#define ACCEL1_DEVICE_PATH "/dev/accel1"
#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 {
float x_offset;
float x_scale;
float y_offset;
float y_scale;
float z_offset;
float z_scale;
};
/*
* ioctl() definitions
*
Expand Down
13 changes: 0 additions & 13 deletions src/drivers/drv_gyro.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,19 +51,6 @@
#define GYRO1_DEVICE_PATH "/dev/gyro1"
#define GYRO2_DEVICE_PATH "/dev/gyro2"

#include <uORB/topics/sensor_gyro.h>
#define gyro_report sensor_gyro_s

/** gyro scaling factors; Vout = (Vin * Vscale) + Voffset */
struct gyro_calibration_s {
float x_offset;
float x_scale;
float y_offset;
float y_scale;
float z_offset;
float z_scale;
};

/*
* ioctl() definitions
*/
Expand Down
55 changes: 30 additions & 25 deletions src/drivers/imu/adis16448/adis16448.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,11 @@
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>

#include <uORB/topics/calibration_accel.h>
#include <uORB/topics/calibration_gyro.h>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/sensor_gyro.h>

#define DIR_READ 0x00
#define DIR_WRITE 0x80

Expand Down Expand Up @@ -224,21 +229,21 @@ class ADIS16448 : public device::SPI

uint16_t _product; /** product code */

struct hrt_call _call;
struct hrt_call _call;
unsigned _call_interval;

ringbuffer::RingBuffer *_gyro_reports;
ringbuffer::RingBuffer *_gyro_reports;

struct gyro_calibration_s _gyro_scale;
calibration_gyro_s _gyro_scale;
float _gyro_range_scale;
float _gyro_range_rad_s;

ringbuffer::RingBuffer *_accel_reports;
ringbuffer::RingBuffer *_accel_reports;

struct accel_calibration_s _accel_scale;
calibration_accel_s _accel_scale;
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
orb_advert_t _accel_topic;
int _accel_orb_class_instance;
int _accel_class_instance;

Expand Down Expand Up @@ -611,13 +616,13 @@ 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;
}

_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;
Expand Down Expand Up @@ -679,7 +684,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 */
Expand All @@ -690,7 +695,7 @@ ADIS16448::init()
warnx("ADVERT FAIL");
}

struct gyro_report grp;
sensor_gyro_s grp;

_gyro_reports->get(&grp);

Expand Down Expand Up @@ -855,7 +860,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) {
Expand All @@ -876,7 +881,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--) {
Expand All @@ -889,7 +894,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
Expand Down Expand Up @@ -926,7 +931,7 @@ ADIS16448::gyro_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) {
Expand All @@ -947,7 +952,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--) {
Expand All @@ -960,7 +965,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
Expand Down Expand Up @@ -1114,7 +1119,7 @@ ADIS16448::ioctl(struct file *filp, int cmd, unsigned long arg)

case ACCELIOCSSCALE: {
/* copy scale, but only if off by a few percent */
struct accel_calibration_s *s = (struct accel_calibration_s *) arg;
calibration_accel_s *s = (calibration_accel_s *) arg;
float sum = s->x_scale + s->y_scale + s->z_scale;

if (sum > 2.0f && sum < 4.0f) {
Expand All @@ -1128,7 +1133,7 @@ ADIS16448::ioctl(struct file *filp, int cmd, unsigned long arg)

case ACCELIOCGSCALE:
/* copy scale out */
memcpy((struct accel_calibration_s *) arg, &_accel_scale, sizeof(_accel_scale));
memcpy((calibration_accel_s *) arg, &_accel_scale, sizeof(_accel_scale));
return OK;

case ACCELIOCSRANGE:
Expand Down Expand Up @@ -1187,12 +1192,12 @@ ADIS16448::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)

case GYROIOCSSCALE:
/* copy scale in */
memcpy(&_gyro_scale, (struct gyro_calibration_s *) arg, sizeof(_gyro_scale));
memcpy(&_gyro_scale, (calibration_gyro_s *) arg, sizeof(_gyro_scale));
return OK;

case GYROIOCGSCALE:
/* copy scale out */
memcpy((struct gyro_calibration_s *) arg, &_gyro_scale, sizeof(_gyro_scale));
memcpy((calibration_gyro_s *) arg, &_gyro_scale, sizeof(_gyro_scale));
return OK;

case GYROIOCSRANGE:
Expand Down Expand Up @@ -1423,8 +1428,8 @@ ADIS16448::measure()
/*
* Report buffers.
*/
accel_report arb;
gyro_report grb;
sensor_accel_s arb;
sensor_gyro_s grb;
mag_report mrb;

grb.timestamp = arb.timestamp = mrb.timestamp = hrt_absolute_time();
Expand Down Expand Up @@ -1826,9 +1831,9 @@ start(enum Rotation rotation)
void
test()
{
accel_report a_report;
gyro_report g_report;
mag_report m_report;
sensor_accel_s a_report;
sensor_gyro_s g_report;
mag_report m_report;

ssize_t sz;

Expand Down
16 changes: 8 additions & 8 deletions src/drivers/imu/adis16477/ADIS16477.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,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);
Expand All @@ -174,7 +174,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) {
Expand Down Expand Up @@ -369,7 +369,7 @@ ADIS16477::ioctl(struct file *filp, int cmd, unsigned long arg)

case ACCELIOCSSCALE: {
/* copy scale, but only if off by a few percent */
struct accel_calibration_s *s = (struct accel_calibration_s *) arg;
calibration_accel_s *s = (calibration_accel_s *) arg;
float sum = s->x_scale + s->y_scale + s->z_scale;

if (sum > 2.0f && sum < 4.0f) {
Expand All @@ -383,7 +383,7 @@ ADIS16477::ioctl(struct file *filp, int cmd, unsigned long arg)

case ACCELIOCGSCALE:
/* copy scale out */
memcpy((struct accel_calibration_s *) arg, &_accel_scale, sizeof(_accel_scale));
memcpy((calibration_accel_s *) arg, &_accel_scale, sizeof(_accel_scale));
return OK;

case ACCELIOCSRANGE:
Expand Down Expand Up @@ -418,12 +418,12 @@ ADIS16477::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)

case GYROIOCSSCALE:
/* copy scale in */
memcpy(&_gyro_scale, (struct gyro_calibration_s *) arg, sizeof(_gyro_scale));
memcpy(&_gyro_scale, (calibration_gyro_s *) arg, sizeof(_gyro_scale));
return OK;

case GYROIOCGSCALE:
/* copy scale out */
memcpy((struct gyro_calibration_s *) arg, &_gyro_scale, sizeof(_gyro_scale));
memcpy((calibration_gyro_s *) arg, &_gyro_scale, sizeof(_gyro_scale));
return OK;

case GYROIOCSRANGE:
Expand Down Expand Up @@ -527,7 +527,7 @@ ADIS16477::publish_accel(const ADISReport &report)
return false;
}

accel_report arb = {};
sensor_accel_s arb = {};
arb.timestamp = hrt_absolute_time();
arb.error_count = perf_event_count(_bad_transfers);

Expand Down Expand Up @@ -586,7 +586,7 @@ ADIS16477::publish_gyro(const ADISReport &report)
return false;
}

gyro_report grb = {};
sensor_gyro_s grb = {};
grb.timestamp = hrt_absolute_time();
grb.error_count = perf_event_count(_bad_transfers);

Expand Down
9 changes: 7 additions & 2 deletions src/drivers/imu/adis16477/ADIS16477.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,11 @@
#include <perf/perf_counter.h>
#include <ecl/geo/geo.h>

#include <uORB/topics/calibration_accel.h>
#include <uORB/topics/calibration_gyro.h>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/sensor_gyro.h>

#define ADIS16477_GYRO_DEFAULT_RATE 250
#define ADIS16477_GYRO_DEFAULT_DRIVER_FILTER_FREQ 30

Expand Down Expand Up @@ -88,13 +93,13 @@ class ADIS16477 : public device::SPI
struct hrt_call _call {};
unsigned _call_interval{0};

struct gyro_calibration_s _gyro_scale {};
calibration_gyro_s _gyro_scale {};

// gyro 0.025 °/sec/LSB
float _gyro_range_scale{0.025f};
float _gyro_range_rad_s{math::radians(500.0f)};

struct accel_calibration_s _accel_scale {};
calibration_accel_s _accel_scale {};

// accel 1.25 mg/LSB
float _accel_range_scale{1.25f * CONSTANTS_ONE_G / 1000.0f};
Expand Down
3 changes: 3 additions & 0 deletions src/drivers/imu/adis16477/ADIS16477_gyro.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,9 @@
#include <drivers/device/CDev.hpp>
#include <drivers/drv_gyro.h>

#include <uORB/topics/calibration_gyro.h>
#include <uORB/topics/sensor_gyro.h>

/**
* Helper class implementing the gyro driver node.
*/
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/imu/adis16477/ADIS16477_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,8 @@ start(enum Rotation rotation)
void
test()
{
accel_report a_report;
gyro_report g_report;
sensor_accel_s a_report;
sensor_gyro_s g_report;

ssize_t sz;

Expand Down
Loading

0 comments on commit 544a1a3

Please sign in to comment.