Browse Source

delete MAGIOCSELFTEST

sbg
Daniel Agar 7 years ago committed by Lorenz Meier
parent
commit
bb9c38a480
  1. 3
      src/drivers/drv_mag.h
  2. 3
      src/drivers/imu/adis16448/adis16448.cpp
  3. 36
      src/drivers/imu/fxos8701cq/fxos8701cq.cpp
  4. 36
      src/drivers/imu/lsm303d/lsm303d.cpp
  5. 9
      src/drivers/imu/mpu9250/mag.cpp
  6. 3
      src/drivers/magnetometer/bmm150/bmm150.cpp
  7. 25
      src/drivers/magnetometer/hmc5883/hmc5883.cpp
  8. 32
      src/drivers/magnetometer/ist8310/ist8310.cpp
  9. 23
      src/drivers/magnetometer/lis3mdl/lis3mdl.cpp
  10. 7
      src/drivers/magnetometer/lis3mdl/lis3mdl.h
  11. 1
      src/drivers/magnetometer/lsm303agr/LSM303AGR.cpp
  12. 3
      src/modules/simulator/accelsim/accelsim.cpp
  13. 4
      src/modules/uavcan/sensors/mag.cpp
  14. 21
      src/systemcmds/config/config.c

3
src/drivers/drv_mag.h

@ -93,9 +93,6 @@ struct mag_calibration_s { @@ -93,9 +93,6 @@ struct mag_calibration_s {
/** excite strap */
#define MAGIOCEXSTRAP _MAGIOC(9)
/** perform self test and report status */
#define MAGIOCSELFTEST _MAGIOC(10)
/** determine if mag is external or onboard */
#define MAGIOCGEXTERNAL _MAGIOC(11)

3
src/drivers/imu/adis16448/adis16448.cpp

@ -1266,9 +1266,6 @@ ADIS16448::mag_ioctl(struct file *filp, int cmd, unsigned long arg) @@ -1266,9 +1266,6 @@ ADIS16448::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCGRANGE:
return (unsigned long)(_mag_range_mgauss);
case MAGIOCSELFTEST:
return OK;
case MAGIOCTYPE:
return (ADIS16448_Product);

36
src/drivers/imu/fxos8701cq/fxos8701cq.cpp

@ -313,13 +313,6 @@ private: @@ -313,13 +313,6 @@ private:
*/
int accel_self_test();
/**
* Mag self test
*
* @return 0 on success, 1 on failure
*/
int mag_self_test();
/**
* Read a register from the FXOS8701C
*
@ -998,9 +991,6 @@ FXOS8701CQ::mag_ioctl(struct file *filp, int cmd, unsigned long arg) @@ -998,9 +991,6 @@ FXOS8701CQ::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCGRANGE:
return _mag_range_ga;
case MAGIOCSELFTEST:
return mag_self_test();
case MAGIOCGEXTERNAL:
/* Even if this sensor is on the "external" SPI bus
* it is still fixed to the autopilot assembly,
@ -1033,32 +1023,6 @@ FXOS8701CQ::accel_self_test() @@ -1033,32 +1023,6 @@ FXOS8701CQ::accel_self_test()
return 0;
}
int
FXOS8701CQ::mag_self_test()
{
if (_mag_read == 0) {
return 1;
}
/**
* inspect mag offsets
* don't check mag scale because it seems this is calibrated on chip
*/
if (fabsf(_mag_scale.x_offset) < 0.000001f) {
return 1;
}
if (fabsf(_mag_scale.y_offset) < 0.000001f) {
return 1;
}
if (fabsf(_mag_scale.z_offset) < 0.000001f) {
return 1;
}
return 0;
}
uint8_t
FXOS8701CQ::read_reg(unsigned reg)
{

36
src/drivers/imu/lsm303d/lsm303d.cpp

@ -378,13 +378,6 @@ private: @@ -378,13 +378,6 @@ private:
*/
int accel_self_test();
/**
* Mag self test
*
* @return 0 on success, 1 on failure
*/
int mag_self_test();
/**
* Read a register from the LSM303D
*
@ -1066,9 +1059,6 @@ LSM303D::mag_ioctl(struct file *filp, int cmd, unsigned long arg) @@ -1066,9 +1059,6 @@ LSM303D::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCGRANGE:
return _mag_range_ga;
case MAGIOCSELFTEST:
return mag_self_test();
case MAGIOCGEXTERNAL:
/* Even if this sensor is on the "external" SPI bus
* it is still fixed to the autopilot assembly,
@ -1092,32 +1082,6 @@ LSM303D::accel_self_test() @@ -1092,32 +1082,6 @@ LSM303D::accel_self_test()
return 0;
}
int
LSM303D::mag_self_test()
{
if (_mag_read == 0) {
return 1;
}
/**
* inspect mag offsets
* don't check mag scale because it seems this is calibrated on chip
*/
if (fabsf(_mag_scale.x_offset) < 0.000001f) {
return 1;
}
if (fabsf(_mag_scale.y_offset) < 0.000001f) {
return 1;
}
if (fabsf(_mag_scale.z_offset) < 0.000001f) {
return 1;
}
return 0;
}
uint8_t
LSM303D::read_reg(unsigned reg)
{

9
src/drivers/imu/mpu9250/mag.cpp

@ -384,9 +384,6 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -384,9 +384,6 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCGRANGE:
return 48; // fixed full scale measurement range of +/- 4800 uT == 48 Gauss
case MAGIOCSELFTEST:
return self_test();
#ifdef MAGIOCSHWLOWPASS
case MAGIOCSHWLOWPASS:
@ -404,12 +401,6 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -404,12 +401,6 @@ MPU9250_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
int
MPU9250_mag::self_test(void)
{
return 0;
}
void
MPU9250_mag::set_passthrough(uint8_t reg, uint8_t size, uint8_t *out)
{

3
src/drivers/magnetometer/bmm150/bmm150.cpp

@ -810,9 +810,6 @@ BMM150::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -810,9 +810,6 @@ BMM150::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCEXSTRAP:
return OK;
case MAGIOCSELFTEST:
return OK;
case MAGIOCSSAMPLERATE:
return ioctl(filp, SENSORIOCSPOLLRATE, arg);

25
src/drivers/magnetometer/hmc5883/hmc5883.cpp

@ -310,13 +310,6 @@ private: @@ -310,13 +310,6 @@ private:
*/
float meas_to_float(uint8_t in[2]);
/**
* Check the current calibration and update device status
*
* @return 0 if calibration is ok, 1 else
*/
int check_calibration();
/**
* Check the current scale calibration
*
@ -724,8 +717,6 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -724,8 +717,6 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCSSCALE:
/* set new scale factors */
memcpy(&_scale, (struct mag_calibration_s *)arg, sizeof(_scale));
/* check calibration, but not actually return an error */
(void)check_calibration();
return 0;
case MAGIOCGSCALE:
@ -739,9 +730,6 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -739,9 +730,6 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCEXSTRAP:
return set_excitement(arg);
case MAGIOCSELFTEST:
return check_calibration();
case MAGIOCGEXTERNAL:
DEVICE_DEBUG("MAGIOCGEXTERNAL in main driver");
return _interface->ioctl(cmd, dummy);
@ -1271,19 +1259,6 @@ int HMC5883::check_offset() @@ -1271,19 +1259,6 @@ int HMC5883::check_offset()
return !offset_valid;
}
int HMC5883::check_calibration()
{
bool offset_valid = (check_offset() == OK);
bool scale_valid = (check_scale() == OK);
if (_calibrated != (offset_valid && scale_valid)) {
_calibrated = (offset_valid && scale_valid);
}
/* return 0 if calibrated, 1 else */
return (!_calibrated);
}
int HMC5883::set_excitement(unsigned enable)
{
int ret;

32
src/drivers/magnetometer/ist8310/ist8310.cpp

@ -357,13 +357,6 @@ private: @@ -357,13 +357,6 @@ private:
*/
float meas_to_float(uint8_t in[2]);
/**
* Check the current calibration and update device status
*
* @return 0 if calibration is ok, 1 else
*/
int check_calibration();
/**
* Check the current scale calibration
*
@ -707,8 +700,6 @@ IST8310::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -707,8 +700,6 @@ IST8310::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCSSCALE:
/* set new scale factors */
memcpy(&_scale, (struct mag_calibration_s *)arg, sizeof(_scale));
/* check calibration, but not actually return an error */
(void)check_calibration();
return 0;
case MAGIOCGSCALE:
@ -719,11 +710,7 @@ IST8310::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -719,11 +710,7 @@ IST8310::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCCALIBRATE:
return calibrate(filp, arg);
case MAGIOCSELFTEST:
return check_calibration();
case MAGIOCGEXTERNAL:
DEVICE_DEBUG("MAGIOCGEXTERNAL in main driver");
return external();
default:
@ -1148,25 +1135,6 @@ int IST8310::check_offset() @@ -1148,25 +1135,6 @@ int IST8310::check_offset()
return !offset_valid;
}
int IST8310::check_calibration()
{
bool offset_valid = (check_offset() == OK);
bool scale_valid = (check_scale() == OK);
if (_calibrated != (offset_valid && scale_valid)) {
if (!scale_valid || !offset_valid) {
PX4_WARN("mag cal status changed %s%s", (scale_valid) ? "" : "scale invalid ",
(offset_valid) ? "" : "offset invalid");
}
_calibrated = (offset_valid && scale_valid);
}
/* return 0 if calibrated, 1 else */
return (!_calibrated);
}
int
IST8310::set_selftest(unsigned enable)
{

23
src/drivers/magnetometer/lis3mdl/lis3mdl.cpp

@ -286,22 +286,6 @@ out: @@ -286,22 +286,6 @@ out:
return ret;
}
int
LIS3MDL::check_calibration()
{
bool offset_valid = (check_offset() == OK);
bool scale_valid = (check_scale() == OK);
if (_calibrated != (offset_valid && scale_valid)) {
PX4_WARN("mag cal status changed %s%s", (scale_valid) ? "" : "scale invalid ",
(offset_valid) ? "" : "offset invalid");
_calibrated = (offset_valid && scale_valid);
}
/* return 0 if calibrated, 1 else */
return !_calibrated;
}
int
LIS3MDL::check_offset()
{
@ -613,8 +597,6 @@ LIS3MDL::ioctl(struct file *file_pointer, int cmd, unsigned long arg) @@ -613,8 +597,6 @@ LIS3MDL::ioctl(struct file *file_pointer, int cmd, unsigned long arg)
case MAGIOCSSCALE:
/* set new scale factors */
memcpy(&_scale, (struct mag_calibration_s *)arg, sizeof(_scale));
/* check calibration, but not actually return an error */
(void)check_calibration();
return 0;
case MAGIOCGSCALE:
@ -622,17 +604,12 @@ LIS3MDL::ioctl(struct file *file_pointer, int cmd, unsigned long arg) @@ -622,17 +604,12 @@ LIS3MDL::ioctl(struct file *file_pointer, int cmd, unsigned long arg)
memcpy((struct mag_calibration_s *)arg, &_scale, sizeof(_scale));
return 0;
case MAGIOCCALIBRATE:
return calibrate(file_pointer, arg);
case MAGIOCEXSTRAP:
return set_excitement(arg);
case MAGIOCSELFTEST:
return check_calibration();
case MAGIOCGEXTERNAL:
DEVICE_DEBUG("MAGIOCGEXTERNAL in main driver");
return _interface->ioctl(cmd, dummy);

7
src/drivers/magnetometer/lis3mdl/lis3mdl.h

@ -199,13 +199,6 @@ private: @@ -199,13 +199,6 @@ private:
*/
int collect();
/**
* Check the current calibration and update device status
*
* @return 0 if calibration is ok, 1 else
*/
int check_calibration();
/**
* Check the current scale calibration
*

1
src/drivers/magnetometer/lsm303agr/LSM303AGR.cpp

@ -331,7 +331,6 @@ LSM303AGR::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -331,7 +331,6 @@ LSM303AGR::ioctl(struct file *filp, int cmd, unsigned long arg)
return 0;
case MAGIOCGEXTERNAL:
DEVICE_DEBUG("MAGIOCGEXTERNAL in main driver");
return external();
default:

3
src/modules/simulator/accelsim/accelsim.cpp

@ -717,9 +717,6 @@ ACCELSIM::mag_ioctl(unsigned long cmd, unsigned long arg) @@ -717,9 +717,6 @@ ACCELSIM::mag_ioctl(unsigned long cmd, unsigned long arg)
*/
return 0;
case MAGIOCSELFTEST:
return OK;
default:
/* give it to the superclass */
return VirtDevObj::devIOCTL(cmd, arg);

4
src/modules/uavcan/sensors/mag.cpp

@ -114,10 +114,6 @@ int UavcanMagnetometerBridge::ioctl(struct file *filp, int cmd, unsigned long ar @@ -114,10 +114,6 @@ int UavcanMagnetometerBridge::ioctl(struct file *filp, int cmd, unsigned long ar
return 0;
}
case MAGIOCSELFTEST: {
return 0; // Nothing to do
}
case MAGIOCGEXTERNAL: {
return 1; // declare it external rise it's priority and to allow for correct orientation compensation
}

21
src/systemcmds/config/config.c

@ -296,27 +296,6 @@ do_mag(int argc, char *argv[]) @@ -296,27 +296,6 @@ do_mag(int argc, char *argv[])
return 1;
}
} else if (argc == 2 && !strcmp(argv[0], "check")) {
ret = ioctl(fd, MAGIOCSELFTEST, 0);
if (ret) {
PX4_WARN("mag self test FAILED! Check calibration:");
struct mag_calibration_s scale;
ret = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&scale);
if (ret) {
PX4_ERR("failed getting mag 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("mag calibration and self test OK");
}
} else {
print_usage();
return 1;

Loading…
Cancel
Save