mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
delete ACCELIOCSELFTEST and GYROIOCSELFTEST
This commit is contained in:
committed by
Lorenz Meier
parent
31c08c7ffb
commit
568a5f1c4c
@@ -94,9 +94,6 @@ struct accel_calibration_s {
|
||||
/** get the current accel measurement range in g */
|
||||
#define ACCELIOCGRANGE _ACCELIOC(8)
|
||||
|
||||
/** get the result of a sensor self-test */
|
||||
#define ACCELIOCSELFTEST _ACCELIOC(9)
|
||||
|
||||
/** determine if hardware is external or onboard */
|
||||
#define ACCELIOCGEXTERNAL _ACCELIOC(12)
|
||||
|
||||
|
||||
@@ -91,9 +91,6 @@ struct gyro_calibration_s {
|
||||
/** get the current gyro measurement range in degrees per second */
|
||||
#define GYROIOCGRANGE _GYROIOC(7)
|
||||
|
||||
/** check the status of the sensor */
|
||||
#define GYROIOCSELFTEST _GYROIOC(8)
|
||||
|
||||
/** get the current gyro type */
|
||||
#define GYROIOCTYPE _GYROIOC(13)
|
||||
|
||||
|
||||
@@ -384,20 +384,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Gyro self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int gyro_self_test();
|
||||
|
||||
/*
|
||||
set low pass filter frequency
|
||||
*/
|
||||
@@ -903,26 +889,6 @@ ADIS16448::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
ADIS16448::accel_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
ADIS16448::gyro_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
ADIS16448::gyro_read(struct file *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
@@ -1137,9 +1103,6 @@ ADIS16448::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
case ACCELIOCTYPE:
|
||||
return (ADIS16448_Product);
|
||||
|
||||
@@ -1202,9 +1165,6 @@ ADIS16448::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case GYROIOCGRANGE:
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return gyro_self_test();
|
||||
|
||||
case GYROIOCTYPE:
|
||||
return (ADIS16448_Product);
|
||||
|
||||
@@ -1260,9 +1220,6 @@ ADIS16448::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
memcpy((struct mag_calibration_s *) arg, &_mag_scale, sizeof(_mag_scale));
|
||||
return OK;
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return -EINVAL;
|
||||
|
||||
case MAGIOCGRANGE:
|
||||
return (unsigned long)(_mag_range_mgauss);
|
||||
|
||||
|
||||
@@ -308,41 +308,6 @@ BMI055_accel::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
BMI055_accel::accel_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* inspect accel offsets */
|
||||
if (fabsf(_accel_scale.x_offset) < 0.000001f) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_accel_scale.x_scale - 1.0f) > 0.4f || fabsf(_accel_scale.x_scale - 1.0f) < 0.000001f) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_accel_scale.y_offset) < 0.000001f) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_accel_scale.y_scale - 1.0f) > 0.4f || fabsf(_accel_scale.y_scale - 1.0f) < 0.000001f) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_accel_scale.z_offset) < 0.000001f) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_accel_scale.z_scale - 1.0f) > 0.4f || fabsf(_accel_scale.z_scale - 1.0f) < 0.000001f) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
deliberately trigger an error in the sensor to trigger recovery
|
||||
*/
|
||||
@@ -484,9 +449,6 @@ BMI055_accel::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -279,13 +279,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/*
|
||||
* set accel sample rate
|
||||
*/
|
||||
|
||||
@@ -256,61 +256,6 @@ BMI055_gyro::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
BMI055_gyro::gyro_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Maximum deviation of 10 degrees
|
||||
*/
|
||||
const float max_offset = (float)(10 * M_PI_F / 180.0f);
|
||||
/* 30% scale error is chosen to catch completely faulty units but
|
||||
* to let some slight scale error pass. Requires a rate table or correlation
|
||||
* with mag rotations + data fit to
|
||||
* calibrate properly and is not done by default.
|
||||
*/
|
||||
const float max_scale = 0.3f;
|
||||
|
||||
/* evaluate gyro offsets, complain if offset -> zero or larger than 30 dps. */
|
||||
if (fabsf(_gyro_scale.x_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* evaluate gyro scale, complain if off by more than 30% */
|
||||
if (fabsf(_gyro_scale.x_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* check if all scales are zero */
|
||||
if ((fabsf(_gyro_scale.x_offset) < 0.000001f) &&
|
||||
(fabsf(_gyro_scale.y_offset) < 0.000001f) &&
|
||||
(fabsf(_gyro_scale.z_offset) < 0.000001f)) {
|
||||
/* if all are zero, this device is not calibrated */
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
deliberately trigger an error in the sensor to trigger recovery
|
||||
*/
|
||||
@@ -479,9 +424,6 @@ BMI055_gyro::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case GYROIOCGRANGE:
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return gyro_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -268,13 +268,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Gyro self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int gyro_self_test();
|
||||
|
||||
/*
|
||||
* set gyro sample rate
|
||||
*/
|
||||
|
||||
@@ -492,63 +492,6 @@ BMI160::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
BMI160::accel_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
BMI160::gyro_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Maximum deviation of 10 degrees
|
||||
*/
|
||||
const float max_offset = (float)(10 * M_PI_F / 180.0f);
|
||||
/* 30% scale error is chosen to catch completely faulty units but
|
||||
* to let some slight scale error pass. Requires a rate table or correlation
|
||||
* with mag rotations + data fit to
|
||||
* calibrate properly and is not done by default.
|
||||
*/
|
||||
const float max_scale = 0.3f;
|
||||
|
||||
/* evaluate gyro offsets, complain if offset -> zero or larger than 30 dps. */
|
||||
if (fabsf(_gyro_scale.x_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* evaluate gyro scale, complain if off by more than 30% */
|
||||
if (fabsf(_gyro_scale.x_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
deliberately trigger an error in the sensor to trigger recovery
|
||||
*/
|
||||
@@ -742,9 +685,6 @@ BMI160::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
@@ -802,9 +742,6 @@ BMI160::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case GYROIOCGRANGE:
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return gyro_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -430,20 +430,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Gyro self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int gyro_self_test();
|
||||
|
||||
/*
|
||||
set low pass filter frequency
|
||||
*/
|
||||
|
||||
@@ -736,9 +736,6 @@ FXAS21002C::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
/* convert to dps and round */
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
@@ -748,7 +745,6 @@ FXAS21002C::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
int
|
||||
FXAS21002C::self_test()
|
||||
{
|
||||
|
||||
if (_read == 0) {
|
||||
return 1;
|
||||
}
|
||||
@@ -756,7 +752,6 @@ FXAS21002C::self_test()
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
uint8_t
|
||||
FXAS21002C::read_reg(unsigned reg)
|
||||
{
|
||||
|
||||
@@ -306,13 +306,6 @@ private:
|
||||
*/
|
||||
void mag_measure();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Read a register from the FXOS8701C
|
||||
*
|
||||
@@ -877,9 +870,6 @@ FXOS8701CQ::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
memcpy((struct accel_calibration_s *) arg, &_accel_scale, sizeof(_accel_scale));
|
||||
return OK;
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
@@ -985,12 +975,6 @@ FXOS8701CQ::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
memcpy((struct mag_calibration_s *) arg, &_mag_scale, sizeof(_mag_scale));
|
||||
return OK;
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return mag_set_range(arg);
|
||||
|
||||
case MAGIOCGRANGE:
|
||||
return _mag_range_ga;
|
||||
|
||||
case MAGIOCGEXTERNAL:
|
||||
/* Even if this sensor is on the "external" SPI bus
|
||||
* it is still fixed to the autopilot assembly,
|
||||
@@ -1004,25 +988,6 @@ FXOS8701CQ::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
FXOS8701CQ::accel_self_test()
|
||||
{
|
||||
/*todo:Implement
|
||||
* set to 2 Jmode Save current samples
|
||||
* Light bit and look for the offsets.
|
||||
* ±2 g mode, X-axis +192
|
||||
* ±2 g mode, Y-axis +270
|
||||
* ±2 g mode, Z-axis +1275
|
||||
*/
|
||||
|
||||
|
||||
if (_accel_read == 0) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t
|
||||
FXOS8701CQ::read_reg(unsigned reg)
|
||||
{
|
||||
|
||||
@@ -685,9 +685,6 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
/* convert to dps and round */
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -371,13 +371,6 @@ private:
|
||||
*/
|
||||
void mag_measure();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Read a register from the LSM303D
|
||||
*
|
||||
@@ -945,9 +938,6 @@ LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
memcpy((struct accel_calibration_s *) arg, &_accel_scale, sizeof(_accel_scale));
|
||||
return OK;
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
@@ -1053,12 +1043,6 @@ LSM303D::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
memcpy((struct mag_calibration_s *) arg, &_mag_scale, sizeof(_mag_scale));
|
||||
return OK;
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return mag_set_range(arg);
|
||||
|
||||
case MAGIOCGRANGE:
|
||||
return _mag_range_ga;
|
||||
|
||||
case MAGIOCGEXTERNAL:
|
||||
/* Even if this sensor is on the "external" SPI bus
|
||||
* it is still fixed to the autopilot assembly,
|
||||
@@ -1072,16 +1056,6 @@ LSM303D::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
LSM303D::accel_self_test()
|
||||
{
|
||||
if (_accel_read == 0) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t
|
||||
LSM303D::read_reg(unsigned reg)
|
||||
{
|
||||
|
||||
@@ -386,20 +386,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Gyro self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int gyro_self_test();
|
||||
|
||||
/*
|
||||
set low pass filter frequency
|
||||
*/
|
||||
@@ -1072,71 +1058,6 @@ MPU6000::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
MPU6000::accel_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
MPU6000::gyro_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Maximum deviation of 20 degrees, according to
|
||||
* http://www.farnell.com/datasheets/1788002.pdf
|
||||
* Section 6.1, initial ZRO tolerance
|
||||
*
|
||||
* 20 dps (0.34 rad/s) initial offset
|
||||
* and 20 dps temperature drift, so 0.34 rad/s * 2
|
||||
*/
|
||||
const float max_offset = 2.0f * 0.34f;
|
||||
|
||||
/* 30% scale error is chosen to catch completely faulty units but
|
||||
* to let some slight scale error pass. Requires a rate table or correlation
|
||||
* with mag rotations + data fit to
|
||||
* calibrate properly and is not done by default.
|
||||
*/
|
||||
const float max_scale = 0.3f;
|
||||
|
||||
/* evaluate gyro offsets, complain if offset -> zero or larger than 20 dps. */
|
||||
if (fabsf(_gyro_scale.x_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* evaluate gyro scale, complain if off by more than 30% */
|
||||
if (fabsf(_gyro_scale.x_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
perform a self-test comparison to factory trim values. This takes
|
||||
about 200ms and will return OK if the current values are within 14%
|
||||
@@ -1485,9 +1406,6 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
case ACCELIOCGEXTERNAL:
|
||||
return _interface->ioctl(cmd, dummy);
|
||||
|
||||
@@ -1553,9 +1471,6 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case GYROIOCGRANGE:
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return gyro_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return CDev::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -378,12 +378,6 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
memcpy((struct mag_scale *) arg, &_mag_scale, sizeof(_mag_scale));
|
||||
return OK;
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return -EINVAL;
|
||||
|
||||
case MAGIOCGRANGE:
|
||||
return 48; // fixed full scale measurement range of +/- 4800 uT == 48 Gauss
|
||||
|
||||
default:
|
||||
return (int)CDev::ioctl(filp, cmd, arg);
|
||||
}
|
||||
|
||||
@@ -674,65 +674,6 @@ MPU9250::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
MPU9250::accel_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
MPU9250::gyro_self_test()
|
||||
{
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Maximum deviation of 20 degrees, according to
|
||||
* http://www.invensense.com/mems/gyro/documents/PS-MPU-9250A-00v3.4.pdf
|
||||
* Section 6.1, initial ZRO tolerance
|
||||
*/
|
||||
const float max_offset = 0.34f;
|
||||
/* 30% scale error is chosen to catch completely faulty units but
|
||||
* to let some slight scale error pass. Requires a rate table or correlation
|
||||
* with mag rotations + data fit to
|
||||
* calibrate properly and is not done by default.
|
||||
*/
|
||||
const float max_scale = 0.3f;
|
||||
|
||||
/* evaluate gyro offsets, complain if offset -> zero or larger than 20 dps. */
|
||||
if (fabsf(_gyro_scale.x_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* evaluate gyro scale, complain if off by more than 30% */
|
||||
if (fabsf(_gyro_scale.x_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
deliberately trigger an error in the sensor to trigger recovery
|
||||
*/
|
||||
@@ -925,9 +866,6 @@ MPU9250::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return CDev::ioctl(filp, cmd, arg);
|
||||
@@ -990,9 +928,6 @@ MPU9250::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case GYROIOCGRANGE:
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return gyro_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return CDev::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -503,20 +503,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Gyro self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int gyro_self_test();
|
||||
|
||||
/*
|
||||
set low pass filter frequency
|
||||
*/
|
||||
|
||||
@@ -816,12 +816,6 @@ BMM150::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
case MAGIOCGSAMPLERATE:
|
||||
return 1000000 / _call_interval;
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return OK;
|
||||
|
||||
case MAGIOCGRANGE:
|
||||
return OK;
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return I2C::ioctl(filp, cmd, arg);
|
||||
|
||||
@@ -688,12 +688,6 @@ IST8310::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
/* same as pollrate because device is in single measurement mode*/
|
||||
return 1000000 / TICK2USEC(_measure_ticks);
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return OK;
|
||||
|
||||
case MAGIOCGRANGE:
|
||||
return 0;
|
||||
|
||||
case MAGIOCEXSTRAP:
|
||||
return set_selftest(arg);
|
||||
|
||||
|
||||
@@ -99,14 +99,6 @@ lis3mdl::init(LIS3MDL_BUS bus_id)
|
||||
PX4_INFO("Poll rate set to max (80hz)");
|
||||
}
|
||||
|
||||
/* Set to 4 Gauss */
|
||||
if (ioctl(fd, MAGIOCSRANGE, 4) != OK) {
|
||||
PX4_WARN("FAILED: MAGIOCSRANGE 4 Gauss");
|
||||
|
||||
} else {
|
||||
PX4_INFO("Set mag range to 4 Gauss");
|
||||
}
|
||||
|
||||
close(fd);
|
||||
|
||||
return true;
|
||||
|
||||
@@ -601,9 +601,6 @@ ACCELSIM::devIOCTL(unsigned long cmd, unsigned long arg)
|
||||
memcpy((struct accel_calibration_s *) arg, &(_accel_scale), sizeof(_accel_scale));
|
||||
return OK;
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return OK;
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return VirtDevObj::devIOCTL(cmd, arg);
|
||||
|
||||
@@ -222,20 +222,6 @@ private:
|
||||
*/
|
||||
int self_test();
|
||||
|
||||
/**
|
||||
* Accel self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int accel_self_test();
|
||||
|
||||
/**
|
||||
* Gyro self test
|
||||
*
|
||||
* @return 0 on success, 1 on failure
|
||||
*/
|
||||
int gyro_self_test();
|
||||
|
||||
/*
|
||||
set sample rate (approximate) - 1kHz to 5Hz
|
||||
*/
|
||||
@@ -599,69 +585,6 @@ GYROSIM::self_test()
|
||||
return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
|
||||
}
|
||||
|
||||
int
|
||||
GYROSIM::accel_self_test()
|
||||
{
|
||||
return OK;
|
||||
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
GYROSIM::gyro_self_test()
|
||||
{
|
||||
return OK;
|
||||
|
||||
if (self_test()) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Maximum deviation of 20 degrees, according to
|
||||
* http://www.invensense.com/mems/gyro/documents/PS-MPU-6000A-00v3.4.pdf
|
||||
* Section 6.1, initial ZRO tolerance
|
||||
*/
|
||||
const float max_offset = 0.34f;
|
||||
/* 30% scale error is chosen to catch completely faulty units but
|
||||
* to let some slight scale error pass. Requires a rate table or correlation
|
||||
* with mag rotations + data fit to
|
||||
* calibrate properly and is not done by default.
|
||||
*/
|
||||
const float max_scale = 0.3f;
|
||||
|
||||
/* evaluate gyro offsets, complain if offset -> zero or larger than 20 dps. */
|
||||
if (fabsf(_gyro_scale.x_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* evaluate gyro scale, complain if off by more than 30% */
|
||||
if (fabsf(_gyro_scale.x_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.y_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_offset) > max_offset) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (fabsf(_gyro_scale.z_scale - 1.0f) > max_scale) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
GYROSIM::gyro_read(void *buffer, size_t buflen)
|
||||
{
|
||||
@@ -812,9 +735,6 @@ GYROSIM::devIOCTL(unsigned long cmd, unsigned long arg)
|
||||
case ACCELIOCGRANGE:
|
||||
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return accel_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return VirtDevObj::devIOCTL(cmd, arg);
|
||||
@@ -872,9 +792,6 @@ GYROSIM::gyro_ioctl(unsigned long cmd, unsigned long arg)
|
||||
case GYROIOCGRANGE:
|
||||
return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return gyro_self_test();
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return VirtDevObj::devIOCTL(cmd, arg);
|
||||
|
||||
@@ -208,27 +208,6 @@ do_gyro(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
} else if (argc == 2 && !strcmp(argv[0], "check")) {
|
||||
ret = ioctl(fd, GYROIOCSELFTEST, 0);
|
||||
|
||||
if (ret) {
|
||||
PX4_WARN("gyro self test FAILED! Check calibration:");
|
||||
struct gyro_calibration_s scale;
|
||||
ret = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&scale);
|
||||
|
||||
if (ret) {
|
||||
PX4_ERR("failed getting gyro scale");
|
||||
return 1;
|
||||
}
|
||||
|
||||
PX4_INFO("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset,
|
||||
(double)scale.z_offset);
|
||||
PX4_INFO("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
|
||||
|
||||
} else {
|
||||
PX4_INFO("gyro calibration and self test OK");
|
||||
}
|
||||
|
||||
} else {
|
||||
print_usage();
|
||||
return 1;
|
||||
@@ -363,27 +342,6 @@ do_accel(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
} else if (argc == 2 && !strcmp(argv[0], "check")) {
|
||||
ret = ioctl(fd, ACCELIOCSELFTEST, 0);
|
||||
|
||||
if (ret) {
|
||||
PX4_WARN("accel self test FAILED! Check calibration:");
|
||||
struct accel_calibration_s scale;
|
||||
ret = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&scale);
|
||||
|
||||
if (ret) {
|
||||
PX4_ERR("failed getting accel scale");
|
||||
return 1;
|
||||
}
|
||||
|
||||
PX4_INFO("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset,
|
||||
(double)scale.z_offset);
|
||||
PX4_INFO("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
|
||||
|
||||
} else {
|
||||
PX4_INFO("accel calibration and self test OK");
|
||||
}
|
||||
|
||||
} else {
|
||||
print_usage();
|
||||
return 1;
|
||||
|
||||
Reference in New Issue
Block a user