Browse Source

Cleanup mpu9250 driver in preparation for PR

sbg
Robert Dickenson 9 years ago committed by Lorenz Meier
parent
commit
95e51ed8c6
  1. 4
      src/drivers/boards/px4fmu-v4/board_config.h
  2. 76
      src/drivers/mpu9250/mag.cpp
  3. 2
      src/drivers/mpu9250/mag.h
  4. 4
      src/drivers/mpu9250/main.cpp
  5. 37
      src/drivers/mpu9250/mpu9250.cpp
  6. 45
      src/systemcmds/mag/CMakeLists.txt
  7. 245
      src/systemcmds/mag/mag.c
  8. 45
      src/systemcmds/mag/module.mk

4
src/drivers/boards/px4fmu-v4/board_config.h

@ -123,8 +123,8 @@ __BEGIN_DECLS @@ -123,8 +123,8 @@ __BEGIN_DECLS
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_RAMTRON
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_GYRO 1
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_MPU 4
#define PX4_SPIDEV_HMC 5
#define PX4_SPIDEV_ICM 6

76
src/drivers/mpu9250/mag.cpp

@ -34,7 +34,7 @@ @@ -34,7 +34,7 @@
/**
* @file mag.cpp
*
* Driver for the ak8963 magnetometer within the Invensense mpu9250.
* Driver for the ak8963 magnetometer within the Invensense mpu9250
*
* @author Robert Dickenson
*
@ -72,6 +72,10 @@ @@ -72,6 +72,10 @@
#define MPU9250_MAG_RANGE_GA 1.5e-3f;
/* we are using the continuous fixed sampling rate of 100Hz */
#define MPU9250_AK8963_SAMPLE_RATE 100
/* mpu9250 master i2c bus specific register address and bit definitions */
@ -126,11 +130,9 @@ MPU9250_mag::MPU9250_mag(MPU9250 *parent, const char *path) : @@ -126,11 +130,9 @@ MPU9250_mag::MPU9250_mag(MPU9250 *parent, const char *path) :
_mag_orb_class_instance(-1),
_mag_class_instance(-1),
_mag_reading_data(false),
_mag_call_interval(0),
_mag_reports(nullptr),
_mag_scale{},
_mag_range_scale(),
_mag_sample_rate(100),
_mag_reads(perf_alloc(PC_COUNT, "mpu9250_mag_read")),
_mag_asa_x(1.0),
_mag_asa_y(1.0),
@ -180,8 +182,6 @@ MPU9250_mag::init() @@ -180,8 +182,6 @@ MPU9250_mag::init()
ak8963_setup();
// measure(0);
/* advertise sensor topic, measure manually to initialize valid report */
struct mag_report mrp;
_mag_reports->get(&mrp);
@ -198,13 +198,6 @@ out: @@ -198,13 +198,6 @@ out:
return ret;
}
uint8_t cnt0 = 0;
uint8_t cnt1 = 0;
uint8_t cnt2 = 0;
uint8_t cnt3 = 0;
uint8_t cnt4 = 0;
void
MPU9250_mag::measure(struct ak8963_regs data)
{
@ -212,38 +205,33 @@ MPU9250_mag::measure(struct ak8963_regs data) @@ -212,38 +205,33 @@ MPU9250_mag::measure(struct ak8963_regs data)
if (data.st1 & 0x01) {
if (false == _mag_reading_data) {
cnt1++;
_parent->write_reg(MPUREG_I2C_SLV0_CTRL, BIT_I2C_SLVO_EN | sizeof(struct ak8963_regs));
_mag_reading_data = true;
return;
} else {
cnt2++;
_parent->write_reg(MPUREG_I2C_SLV0_CTRL, BIT_I2C_SLVO_EN | 1);
_mag_reading_data = false;
}
} else {
if (true == _mag_reading_data) {
cnt4++;
_parent->write_reg(MPUREG_I2C_SLV0_CTRL, BIT_I2C_SLVO_EN | 1);
_mag_reading_data = false;
} else {
cnt3++;
}
return;
}
mag_report mrb;
mag_report mrb;
mrb.timestamp = hrt_absolute_time();
/*
* Align axes - note the accel & gryo are also re-aligned so this
* doesn't look obvious with the datasheet
*/
mrb.x_raw = data.x;
mrb.x_raw = data.x;
mrb.y_raw = -data.y;
mrb.z_raw = -data.z;
float xraw_f = data.x;
float xraw_f = data.x;
float yraw_f = -data.y;
float zraw_f = -data.z;
@ -257,13 +245,7 @@ MPU9250_mag::measure(struct ak8963_regs data) @@ -257,13 +245,7 @@ MPU9250_mag::measure(struct ak8963_regs data)
mrb.scaling = _mag_range_scale;
mrb.temperature = _parent->_last_temperature;
static uint64_t prev_mag_timestamp = 0;
mrb.error_count = ((uint64_t)(mrb.timestamp - prev_mag_timestamp) << 40)
+ ((uint64_t)cnt0 << 32)
+ ((uint32_t)cnt1 << 24) + ((uint32_t)cnt2 << 16)
+ ((uint32_t)cnt3 << 8) + cnt4;
cnt0 = cnt1 = cnt2 = cnt3 = cnt4 = 0;
prev_mag_timestamp = mrb.timestamp;
mrb.error_count = 0;
_mag_reports->force(&mrb);
@ -289,8 +271,11 @@ MPU9250_mag::read(struct file *filp, char *buffer, size_t buflen) @@ -289,8 +271,11 @@ MPU9250_mag::read(struct file *filp, char *buffer, size_t buflen)
}
/* if automatic measurement is not enabled, get a fresh measurement into the buffer */
if (_mag_call_interval == 0) {
if (_parent->_call_interval == 0) {
_mag_reports->flush();
/* TODO: this won't work as getting valid magnetometer
* data requires more than one measure cycle
*/
_parent->measure();
}
@ -323,8 +308,10 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -323,8 +308,10 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
switch (cmd) {
case SENSORIOCRESET:
// TODO: we could implement a reset of the AK8963 registers
// return reset();
/*
* TODO: we could implement a reset of the AK8963 registers
*/
//return reset();
return _parent->ioctl(filp, cmd, arg);
case SENSORIOCSPOLLRATE: {
@ -332,8 +319,11 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -332,8 +319,11 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
/* switching to manual polling */
case SENSOR_POLLRATE_MANUAL:
// stop();
_mag_call_interval = 0;
/*
* TODO: investigate being able to stop
* the continuous sampling
*/
//stop();
return OK;
/* external signalling not supported */
@ -347,15 +337,12 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -347,15 +337,12 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSOR_POLLRATE_MAX:
return ioctl(filp, SENSORIOCSPOLLRATE, 100);
#define MPU9250_AK8963_DEFAULT_RATE 100
#define MPU9250_AK8963_TIMER_REDUCTION 0
case SENSOR_POLLRATE_DEFAULT:
return ioctl(filp, SENSORIOCSPOLLRATE, MPU9250_AK8963_DEFAULT_RATE);
return ioctl(filp, SENSORIOCSPOLLRATE, MPU9250_AK8963_SAMPLE_RATE);
/* adjust to a legal polling interval in Hz */
default: {
if (MPU9250_AK8963_DEFAULT_RATE != arg) {
if (MPU9250_AK8963_SAMPLE_RATE != arg) {
return -EINVAL;
}
return OK;
@ -364,7 +351,7 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -364,7 +351,7 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
}
case SENSORIOCGPOLLRATE:
return MPU9250_AK8963_DEFAULT_RATE;
return MPU9250_AK8963_SAMPLE_RATE;
case SENSORIOCSQUEUEDEPTH: {
/* lower bound is mandatory, upper bound is a sanity check */
@ -388,13 +375,14 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -388,13 +375,14 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
return _mag_reports->size();
case MAGIOCGSAMPLERATE:
return _mag_sample_rate;
return MPU9250_AK8963_SAMPLE_RATE;
case MAGIOCSSAMPLERATE:
/*
* We don't currently support any means of changing the sampling rate of the mag
*/
if (MPU9250_AK8963_DEFAULT_RATE != arg) {
/*
* We don't currently support any means of changing
* the sampling rate of the mag
*/
if (MPU9250_AK8963_SAMPLE_RATE != arg) {
return -EINVAL;
}
return OK;
@ -482,7 +470,7 @@ MPU9250_mag::ak8963_check_id(void) @@ -482,7 +470,7 @@ MPU9250_mag::ak8963_check_id(void)
for (int i = 0; i < 5; i++) {
uint8_t deviceid = 0;
passthrough_read(AK8963REG_WIA, &deviceid, 0x01);
if (deviceid == AK8963_DEVICE_ID) {
if (AK8963_DEVICE_ID == deviceid) {
return true;
}
}

2
src/drivers/mpu9250/mag.h

@ -78,11 +78,9 @@ private: @@ -78,11 +78,9 @@ private:
int _mag_orb_class_instance;
int _mag_class_instance;
bool _mag_reading_data;
unsigned _mag_call_interval;
ringbuffer::RingBuffer *_mag_reports;
struct mag_scale _mag_scale;
float _mag_range_scale;
unsigned _mag_sample_rate;
perf_counter_t _mag_reads;
float _mag_asa_x;
float _mag_asa_y;

4
src/drivers/mpu9250/main.cpp

@ -78,7 +78,7 @@ @@ -78,7 +78,7 @@
#define MPU_DEVICE_PATH_MAG "/dev/mpu9250_mag"
#define MPU_DEVICE_PATH_ACCEL_EXT "/dev/mpu9250_accel_ext"
#define MPU_DEVICE_PATH_GYRO_EXT "/dev/mpu9250_gyro_ext"
#define MPU_DEVICE_PATH_MAG_EXT "/dev/mpu9250_mag_ext"
#define MPU_DEVICE_PATH_MAG_EXT "/dev/mpu9250_mag_ext"
/** driver 'main' command */
extern "C" { __EXPORT int mpu9250_main(int argc, char *argv[]); }
@ -100,8 +100,6 @@ void info(bool); @@ -100,8 +100,6 @@ void info(bool);
void regdump(bool);
void testerror(bool);
void usage();
void w(bool);
void g(bool, char *);
/**
* Start the driver.

37
src/drivers/mpu9250/mpu9250.cpp

@ -182,10 +182,6 @@ @@ -182,10 +182,6 @@
#define MPU9250_GYRO_MAX_OUTPUT_RATE MPU9250_ACCEL_MAX_OUTPUT_RATE
#define MPU9250_GYRO_DEFAULT_DRIVER_FILTER_FREQ 30
#define MPU9250_MAG_DEFAULT_RATE 1000
#define MPU9250_MAG_MAX_OUTPUT_RATE MPU9250_GYRO_MAX_OUTPUT_RATE
#define MPU9250_MAG_DEFAULT_DRIVER_FILTER_FREQ 30
#define MPU9250_DEFAULT_ONCHIP_FILTER_FREQ 41
#define MPU9250_ONE_G 9.80665f
@ -259,7 +255,6 @@ MPU9250::MPU9250(int bus, const char *path_accel, const char *path_gyro, const c @@ -259,7 +255,6 @@ MPU9250::MPU9250(int bus, const char *path_accel, const char *path_gyro, const c
_rotation(rotation),
_checked_next(0),
_last_temperature(0),
// _last_accel{},
_last_accel_data{},
_got_duplicate(false)
{
@ -391,7 +386,7 @@ MPU9250::init() @@ -391,7 +386,7 @@ MPU9250::init()
return ret;
}
/* do CDev init for the gyro device node, keep it optional */
/* do CDev init for the mag device node, keep it optional */
ret = _mag->init();
/* if probe/setup failed, bail now */
@ -736,19 +731,20 @@ MPU9250::gyro_self_test() @@ -736,19 +731,20 @@ MPU9250::gyro_self_test()
void
MPU9250::test_error()
{
// deliberately trigger an error. This was noticed during
// development as a handy way to test the reset logic
uint8_t data[16];
memset(data, 0, sizeof(data));
transfer(data, data, sizeof(data));
::printf("error triggered\n");
print_registers();
// deliberately trigger an error. This was noticed during
// development as a handy way to test the reset logic
uint8_t data[16];
memset(data, 0, sizeof(data));
transfer(data, data, sizeof(data));
::printf("error triggered\n");
print_registers();
}
ssize_t
MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(gyro_report);
/* buffer must be large enough */
if (count < 1) {
return -ENOSPC;
@ -775,6 +771,7 @@ MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen) @@ -775,6 +771,7 @@ MPU9250::gyro_read(struct file *filp, char *buffer, size_t buflen)
if (!_gyro_reports->get(grp)) {
break;
}
transferred++;
grp++;
}
@ -938,12 +935,14 @@ MPU9250::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -938,12 +935,14 @@ MPU9250::ioctl(struct file *filp, int cmd, unsigned long arg)
return accel_self_test();
#ifdef ACCELIOCSHWLOWPASS
case ACCELIOCSHWLOWPASS:
_set_dlpf_filter(arg);
return OK;
#endif
#ifdef ACCELIOCGHWLOWPASS
case ACCELIOCGHWLOWPASS:
return _dlpf_freq;
#endif
@ -1027,19 +1026,21 @@ MPU9250::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) @@ -1027,19 +1026,21 @@ MPU9250::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
return gyro_self_test();
#ifdef GYROIOCSHWLOWPASS
case GYROIOCSHWLOWPASS:
_set_dlpf_filter(arg);
return OK;
#endif
#ifdef GYROIOCGHWLOWPASS
case GYROIOCGHWLOWPASS:
return _dlpf_freq;
#endif
default:
/* give it to the superclass */
return SPI::ioctl(filp, cmd, arg);
/* give it to the superclass */
return SPI::ioctl(filp, cmd, arg);
}
}
@ -1312,8 +1313,6 @@ MPU9250::measure() @@ -1312,8 +1313,6 @@ MPU9250::measure()
check_registers();
if (check_duplicate(&mpu_report.accel_x[0])) {
extern uint8_t cnt0;
cnt0++;
return;
}
@ -1361,7 +1360,7 @@ cnt0++; @@ -1361,7 +1360,7 @@ cnt0++;
/*
* Report buffers.
*/
accel_report arb;
accel_report arb;
gyro_report grb;
/*
@ -1419,7 +1418,7 @@ cnt0++; @@ -1419,7 +1418,7 @@ cnt0++;
arb.y_integral = aval_integrated(1);
arb.z_integral = aval_integrated(2);
arb.scaling = _accel_range_scale;
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
_last_temperature = (report.temp) / 361.0f + 35.0f;

45
src/systemcmds/mag/CMakeLists.txt

@ -1,45 +0,0 @@ @@ -1,45 +0,0 @@
############################################################################
#
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE systemcmds__mag
MAIN mag
PRIORITY "SCHED_PRIORITY_DEFAULT-30"
STACK 1500
COMPILE_FLAGS
-Os
SRCS
mag.c
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

245
src/systemcmds/mag/mag.c

@ -1,245 +0,0 @@ @@ -1,245 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
* Author: Robert Dickenson
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mag.c
*
* Utility for viewing magnetometer ORB publications, specifically for
* development work on the Invensense mpu9250 connected via SPI.
*
* @author Robert Dickenson
*
*/
#include <px4_config.h>
#include <termios.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdarg.h>
#include <unistd.h>
#include <stdlib.h>
#include <errno.h>
#include <apps/nsh.h>
#include <fcntl.h>
#include <poll.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_mag.h>
#define mag_report sensor_mag_s
/*
struct sensor_mag_s {
uint64_t timestamp;
uint64_t error_count;
float x;
float y;
float z;
float range_ga;
float scaling;
float temperature;
int16_t x_raw;
int16_t y_raw;
int16_t z_raw;
};
*/
int mag1(void);
int mag2(void);
int
mag1(void)
{
int16_t x_raw = 0;
int16_t y_raw = 0;
int16_t z_raw = 0;
struct mag_report mrb;
int mag_fd = orb_subscribe(ORB_ID(sensor_mag));
while (true) {
bool updated = false;
orb_check(mag_fd, &updated);
if (updated) {
orb_copy(ORB_ID(sensor_mag), mag_fd, &mrb);
// printf("magxyz %d %d %d ", mrb.x_raw, mrb.y_raw, mrb.z_raw);
printf("magxyz %8.4f %8.4f %8.4f ", (double)mrb.x, (double)mrb.y, (double)mrb.z);
uint8_t cnt0 = (mrb.error_count & 0x000000FF00000000) >> 32;
uint8_t cnt1 = (mrb.error_count & 0x00000000FF000000) >> 24;
uint8_t cnt2 = (mrb.error_count & 0x0000000000FF0000) >> 16;
uint8_t cnt3 = (mrb.error_count & 0x000000000000FF00) >> 8;
uint8_t cnt4 = (mrb.error_count & 0x00000000000000FF);
printf("[%x %x %x %x %x] ", cnt0, cnt1, cnt2, cnt3, cnt4);
uint32_t mag_interval = (mrb.error_count & 0xFFFFFF0000000000) >> 40;
printf("%u ", mag_interval);
if ((mag_interval) < 5000) {
printf("* ");
}
if ((mag_interval) > 15000) {
printf("! ");
}
if (mrb.x_raw == x_raw && mrb.y_raw == y_raw && mrb.z_raw == z_raw ) {
printf("dup "); // duplicate magnetometer xyz data
}
x_raw = mrb.x_raw;
y_raw = mrb.y_raw;
z_raw = mrb.z_raw;
printf("\n");
}
struct pollfd fds;
int ret;
fds.fd = 0; /* stdin */
fds.events = POLLIN;
ret = poll(&fds, 1, 0);
if (ret > 0) {
char c;
read(0, &c, 1);
switch (c) {
case 0x03: // ctrl-c
case 0x1b: // esc
case 'c':
case 'q':
return OK;
}
}
}
return OK;
}
#define MAX_SAMPLES 100
static struct mag_report mrb[MAX_SAMPLES];
static uint64_t last_timestamp;
int
mag2(void)
{
int i = 0;
int mag_fd = orb_subscribe(ORB_ID(sensor_mag));
while (i < MAX_SAMPLES) {
bool updated = false;
orb_check(mag_fd, &updated);
if (updated) {
orb_copy(ORB_ID(sensor_mag), mag_fd, &mrb[i++]);
}
/*
struct pollfd fds;
int ret;
fds.fd = 0; // stdin
fds.events = POLLIN;
ret = poll(&fds, 1, 0);
if (ret > 0) {
char c;
read(0, &c, 1);
switch (c) {
case 0x03: // ctrl-c
case 0x1b: // esc
case 'c':
case 'q':
return OK;
}
}
*/
}
uint32_t total_time = 0;
last_timestamp = mrb[0].timestamp;
for (i = 0; i < MAX_SAMPLES; i++) {
// printf("magxyz %d %d %d ", mrb[i].x_raw, mrb[i].y_raw, mrb[i].z_raw);
printf("magxyz %8.4f %8.4f %8.4f ", (double)mrb[i].x, (double)mrb[i].y, (double)mrb[i].z);
uint8_t cnt0 = (mrb[i].error_count & 0x000000FF00000000) >> 32;
uint8_t cnt1 = (mrb[i].error_count & 0x00000000FF000000) >> 24;
uint8_t cnt2 = (mrb[i].error_count & 0x0000000000FF0000) >> 16;
uint8_t cnt3 = (mrb[i].error_count & 0x000000000000FF00) >> 8;
uint8_t cnt4 = (mrb[i].error_count & 0x00000000000000FF);
printf("[%x %x %x %x %x] ", cnt0, cnt1, cnt2, cnt3, cnt4);
uint32_t mag_interval = (mrb[i].error_count & 0xFFFFFF0000000000) >> 40;
printf("%u ", mag_interval);
if ((mag_interval) < 5000) {
printf("* ");
}
if ((mag_interval) > 15000) {
printf("! ");
}
uint32_t orb_interval = mrb[i].timestamp - last_timestamp;
if (orb_interval != mag_interval) {
printf("orb ", orb_interval); // missed some orb publications
}
last_timestamp = mrb[i].timestamp;
total_time += orb_interval;
if (mrb[i].x_raw == mrb[i-1].x_raw && mrb[i].y_raw == mrb[i-1].y_raw && mrb[i].z_raw == mrb[i-1].z_raw ) {
printf("dup "); // duplicate magnetometer xyz data
}
printf("\n");
}
double t = (double)total_time / 1000000.0;
printf("total_time: %.3f s\n", t);
return OK;
}
__EXPORT int mag_main(int argc, char *argv[]);
int
mag_main(int argc, char *argv[])
{
if (argc < 2) {
mag1();
} else {
int reps = atoi(argv[1]);
if (reps > 20 || reps < 1) {
reps = 1;
}
while (reps--) {
mag2();
}
}
return OK;
}

45
src/systemcmds/mag/module.mk

@ -1,45 +0,0 @@ @@ -1,45 +0,0 @@
############################################################################
#
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Build mag utility
#
MODULE_COMMAND = mag
SRCS = mag.c
MODULE_STACKSIZE = 1500
MAXOPTIMIZATION = -Os
MODULE_PRIORITY = "SCHED_PRIORITY_DEFAULT-30"
Loading…
Cancel
Save