From e164281a2eca2b429c907d4c1819b9a25c262a96 Mon Sep 17 00:00:00 2001
From: Daniel Agar <daniel@agar.ca>
Date: Sun, 4 Nov 2018 20:36:32 -0500
Subject: [PATCH] mpu6000 remove interface IOCTLs

---
 src/drivers/imu/mpu6000/mpu6000.cpp     | 10 +---
 src/drivers/imu/mpu6000/mpu6000.h       |  8 ---
 src/drivers/imu/mpu6000/mpu6000_i2c.cpp | 45 ++------------
 src/drivers/imu/mpu6000/mpu6000_spi.cpp | 79 +++----------------------
 4 files changed, 13 insertions(+), 129 deletions(-)

diff --git a/src/drivers/imu/mpu6000/mpu6000.cpp b/src/drivers/imu/mpu6000/mpu6000.cpp
index 58d027c2f9..3c1eda6246 100644
--- a/src/drivers/imu/mpu6000/mpu6000.cpp
+++ b/src/drivers/imu/mpu6000/mpu6000.cpp
@@ -133,6 +133,7 @@ class MPU6000 : public device::CDev
 public:
 	MPU6000(device::Device *interface, const char *path_accel, const char *path_gyro, enum Rotation rotation,
 		int device_type);
+
 	virtual ~MPU6000();
 
 	virtual int		init();
@@ -605,17 +606,13 @@ MPU6000::init()
 {
 
 #if defined(USE_I2C)
-	unsigned dummy;
-	use_i2c(_interface->ioctl(MPUIOCGIS_I2C, dummy));
+	use_i2c(_interface->get_device_bus_type() == Device::DeviceBusType_I2C);
 #endif
 
-
 	/* probe again to get our settings that are based on the device type */
-
 	int ret = probe();
 
 	/* if probe failed, bail now */
-
 	if (ret != OK) {
 
 		DEVICE_DEBUG("CDev init failed");
@@ -1380,7 +1377,6 @@ MPU6000::read_reg16(unsigned reg)
 	uint8_t buf[2];
 
 	// general register transfer at low clock speed
-
 	_interface->read(MPU6000_LOW_SPEED_OP(reg), &buf, arraySize(buf));
 	return (uint16_t)(buf[0] << 8) | buf[1];
 }
@@ -1389,7 +1385,6 @@ int
 MPU6000::write_reg(unsigned reg, uint8_t value)
 {
 	// general register transfer at low clock speed
-
 	return _interface->write(MPU6000_LOW_SPEED_OP(reg), &value, 1);
 }
 
@@ -1495,7 +1490,6 @@ MPU6000::start()
 void
 MPU6000::stop()
 {
-
 	if (!is_i2c()) {
 		hrt_cancel(&_call);
 
diff --git a/src/drivers/imu/mpu6000/mpu6000.h b/src/drivers/imu/mpu6000/mpu6000.h
index 0b5855e0d2..55e7c873ae 100644
--- a/src/drivers/imu/mpu6000/mpu6000.h
+++ b/src/drivers/imu/mpu6000/mpu6000.h
@@ -214,14 +214,6 @@
 
 #define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ			98
 
-#ifdef PX4_SPI_BUS_EXT
-#define EXTERNAL_BUS PX4_SPI_BUS_EXT
-#else
-#define EXTERNAL_BUS 0
-#endif
-
-#define MPUIOCGIS_I2C	(unsigned)(DEVIOCGDEVICEID+100)
-
 #pragma pack(push, 1)
 /**
  * Report conversation within the MPU6000, including command byte and
diff --git a/src/drivers/imu/mpu6000/mpu6000_i2c.cpp b/src/drivers/imu/mpu6000/mpu6000_i2c.cpp
index cfb1b8870d..b9282e707f 100644
--- a/src/drivers/imu/mpu6000/mpu6000_i2c.cpp
+++ b/src/drivers/imu/mpu6000/mpu6000_i2c.cpp
@@ -37,28 +37,13 @@
  * I2C interface for MPU6000 /MPU6050
  */
 
-/* XXX trim includes */
 #include <px4_config.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <string.h>
-#include <assert.h>
-#include <debug.h>
-#include <errno.h>
-#include <unistd.h>
-
-#include <arch/board/board.h>
-
 #include <drivers/device/i2c.h>
 #include <drivers/drv_accel.h>
 #include <drivers/drv_device.h>
 
 #include "mpu6000.h"
 
-#include "board_config.h"
-
 #ifdef USE_I2C
 
 device::Device *MPU6000_I2C_interface(int bus, int device_type, bool external_bus);
@@ -67,15 +52,13 @@ class MPU6000_I2C : public device::I2C
 {
 public:
 	MPU6000_I2C(int bus, int device_type);
-	virtual ~MPU6000_I2C() = default;
+	~MPU6000_I2C() override = default;
 
-	virtual int	read(unsigned address, void *data, unsigned count);
-	virtual int	write(unsigned address, void *data, unsigned count);
-
-	virtual int	ioctl(unsigned operation, unsigned &arg);
+	int	read(unsigned address, void *data, unsigned count) override;
+	int	write(unsigned address, void *data, unsigned count) override;
 
 protected:
-	virtual int	probe();
+	int	probe() override;
 
 private:
 	int _device_type;
@@ -96,25 +79,6 @@ MPU6000_I2C::MPU6000_I2C(int bus, int device_type) :
 	_device_id.devid_s.devtype =  DRV_ACC_DEVTYPE_MPU6000;
 }
 
-int
-MPU6000_I2C::ioctl(unsigned operation, unsigned &arg)
-{
-	int ret;
-
-	switch (operation) {
-	case DEVIOCGDEVICEID:
-		return CDev::ioctl(nullptr, operation, arg);
-
-	case MPUIOCGIS_I2C:
-		return 1;
-
-	default:
-		ret = -EINVAL;
-	}
-
-	return ret;
-}
-
 int
 MPU6000_I2C::write(unsigned reg_speed, void *data, unsigned count)
 {
@@ -144,7 +108,6 @@ MPU6000_I2C::read(unsigned reg_speed, void *data, unsigned count)
 	return ret == OK ? count : ret;
 }
 
-
 int
 MPU6000_I2C::probe()
 {
diff --git a/src/drivers/imu/mpu6000/mpu6000_spi.cpp b/src/drivers/imu/mpu6000/mpu6000_spi.cpp
index 1a8e21229a..4da53a987b 100644
--- a/src/drivers/imu/mpu6000/mpu6000_spi.cpp
+++ b/src/drivers/imu/mpu6000/mpu6000_spi.cpp
@@ -42,34 +42,18 @@
  */
 
 #include <px4_config.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <string.h>
-#include <assert.h>
-#include <debug.h>
-#include <errno.h>
-#include <unistd.h>
-
-#include <arch/board/board.h>
-
 #include <drivers/device/spi.h>
 #include <drivers/drv_accel.h>
 #include <drivers/drv_device.h>
 
 #include "mpu6000.h"
-#include <board_config.h>
+
+#include <string.h>
 
 #define DIR_READ			0x80
 #define DIR_WRITE			0x00
 
 #if defined(PX4_SPIDEV_MPU) || defined(PX4_SPIDEV_ICM_20602) || defined(PX4_SPIDEV_ICM_20689)
-#  ifdef PX4_SPI_BUS_EXT
-#    define EXTERNAL_BUS PX4_SPI_BUS_EXT
-#  else
-#    define EXTERNAL_BUS 0
-#  endif
 
 /* The MPU6000 can only handle high SPI bus speeds of 20Mhz on the sensor and
 * interrupt status registers. All other registers have a maximum 1MHz
@@ -101,15 +85,13 @@ class MPU6000_SPI : public device::SPI
 {
 public:
 	MPU6000_SPI(int bus, uint32_t device, int device_type);
-	virtual ~MPU6000_SPI() = default;
+	~MPU6000_SPI() override = default;
 
-	virtual int	init();
-	virtual int	read(unsigned address, void *data, unsigned count);
-	virtual int	write(unsigned address, void *data, unsigned count);
+	int	read(unsigned address, void *data, unsigned count) override;
+	int	write(unsigned address, void *data, unsigned count) override;
 
-	virtual int	ioctl(unsigned operation, unsigned &arg);
 protected:
-	virtual int probe();
+	int probe() override;
 
 private:
 
@@ -199,7 +181,6 @@ MPU6000_SPI_interface(int bus, int device_type, bool external_bus)
 	}
 
 	if (cs != SPIDEV_NONE(0)) {
-
 		interface = new MPU6000_SPI(bus,  cs, device_type);
 	}
 
@@ -210,57 +191,19 @@ MPU6000_SPI::MPU6000_SPI(int bus, uint32_t device, int device_type) :
 	SPI("MPU6000", nullptr, bus, device, SPIDEV_MODE3, MPU6000_LOW_SPI_BUS_SPEED),
 	_device_type(device_type)
 {
-	_device_id.devid_s.devtype =  DRV_ACC_DEVTYPE_MPU6000;
-}
-
-int
-MPU6000_SPI::init()
-{
-	int ret;
-
-	ret = SPI::init();
-
-	if (ret != OK) {
-		DEVICE_DEBUG("SPI init failed");
-		return -EIO;
-	}
-
-	return OK;
-}
-
-int
-MPU6000_SPI::ioctl(unsigned operation, unsigned &arg)
-{
-	int ret;
-
-	switch (operation) {
-	case DEVIOCGDEVICEID:
-		return CDev::ioctl(nullptr, operation, arg);
-
-	case MPUIOCGIS_I2C:
-		return 0;
-
-	default: {
-			ret = -EINVAL;
-		}
-	}
-
-	return ret;
+	_device_id.devid_s.devtype = DRV_ACC_DEVTYPE_MPU6000;
 }
 
 void
 MPU6000_SPI::set_bus_frequency(unsigned &reg_speed)
 {
 	/* Set the desired speed */
-
 	set_frequency(MPU6000_IS_HIGH_SPEED(reg_speed) ? _max_frequency : MPU6000_LOW_SPI_BUS_SPEED);
 
 	/* Isolate the register on return */
-
 	reg_speed = MPU6000_REG(reg_speed);
 }
 
-
 int
 MPU6000_SPI::write(unsigned reg_speed, void *data, unsigned count)
 {
@@ -271,7 +214,6 @@ MPU6000_SPI::write(unsigned reg_speed, void *data, unsigned count)
 	}
 
 	/* Set the desired speed and isolate the register */
-
 	set_bus_frequency(reg_speed);
 
 	cmd[0] = reg_speed | DIR_WRITE;
@@ -292,32 +234,25 @@ MPU6000_SPI::read(unsigned reg_speed, void *data, unsigned count)
 
 	uint8_t *pbuff  =  count < sizeof(MPUReport) ? cmd : (uint8_t *) data ;
 
-
 	if (count < sizeof(MPUReport))  {
-
 		/* add command */
-
 		count++;
 	}
 
 	set_bus_frequency(reg_speed);
 
 	/* Set command */
-
 	pbuff[0] = reg_speed | DIR_READ ;
 
 	/* Transfer the command and get the data */
-
 	int ret = transfer(pbuff, pbuff, count);
 
 	if (ret == OK && pbuff == &cmd[0]) {
 
 		/* Adjust the count back */
-
 		count--;
 
 		/* Return the data */
-
 		memcpy(data, &cmd[1], count);
 
 	}
-- 
GitLab