[PATCH 08/11] staging:iio:adis16260: Use adis library

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

 



Use the new adis library for the adis16260 driver. This allows us to completely
scrap the adis16260 buffer and trigger code and about half of the core driver
code.

Signed-off-by: Lars-Peter Clausen <lars@xxxxxxxxxx>
---
 drivers/staging/iio/gyro/Makefile            |   1 -
 drivers/staging/iio/gyro/adis16260.h         |  84 +----
 drivers/staging/iio/gyro/adis16260_core.c    | 483 +++++----------------------
 drivers/staging/iio/gyro/adis16260_ring.c    | 136 --------
 drivers/staging/iio/gyro/adis16260_trigger.c |  75 -----
 5 files changed, 94 insertions(+), 685 deletions(-)
 delete mode 100644 drivers/staging/iio/gyro/adis16260_ring.c
 delete mode 100644 drivers/staging/iio/gyro/adis16260_trigger.c

diff --git a/drivers/staging/iio/gyro/Makefile b/drivers/staging/iio/gyro/Makefile
index 9ba5ec1..1303569 100644
--- a/drivers/staging/iio/gyro/Makefile
+++ b/drivers/staging/iio/gyro/Makefile
@@ -12,7 +12,6 @@ adis16130-y             := adis16130_core.o
 obj-$(CONFIG_ADIS16130) += adis16130.o
 
 adis16260-y             := adis16260_core.o
-adis16260-$(CONFIG_IIO_BUFFER) += adis16260_ring.o adis16260_trigger.o
 obj-$(CONFIG_ADIS16260) += adis16260.o
 
 adis16251-y             := adis16251_core.o
diff --git a/drivers/staging/iio/gyro/adis16260.h b/drivers/staging/iio/gyro/adis16260.h
index 4c4b251..ea5eba2 100644
--- a/drivers/staging/iio/gyro/adis16260.h
+++ b/drivers/staging/iio/gyro/adis16260.h
@@ -1,12 +1,11 @@
 #ifndef SPI_ADIS16260_H_
 #define SPI_ADIS16260_H_
+
 #include "adis16260_platform_data.h"
+#include "../imu/adis.h"
 
 #define ADIS16260_STARTUP_DELAY	220 /* ms */
 
-#define ADIS16260_READ_REG(a)    a
-#define ADIS16260_WRITE_REG(a) ((a) | 0x80)
-
 #define ADIS16260_FLASH_CNT  0x00 /* Flash memory write count */
 #define ADIS16260_SUPPLY_OUT 0x02 /* Power supply measurement */
 #define ADIS16260_GYRO_OUT   0x04 /* X-axis gyroscope output */
@@ -34,8 +33,6 @@
 				   * convert to decimal = 16,265/16,260 */
 #define ADIS16260_SERIAL_NUM 0x58 /* Serial number */
 
-#define ADIS16260_OUTPUTS    5
-
 #define ADIS16260_ERROR_ACTIVE			(1<<14)
 #define ADIS16260_NEW_DATA			(1<<15)
 
@@ -60,13 +57,13 @@
 /* DIAG_STAT */
 #define ADIS16260_DIAG_STAT_ALARM2	(1<<9)
 #define ADIS16260_DIAG_STAT_ALARM1	(1<<8)
-#define ADIS16260_DIAG_STAT_FLASH_CHK	(1<<6)
-#define ADIS16260_DIAG_STAT_SELF_TEST	(1<<5)
-#define ADIS16260_DIAG_STAT_OVERFLOW	(1<<4)
-#define ADIS16260_DIAG_STAT_SPI_FAIL	(1<<3)
-#define ADIS16260_DIAG_STAT_FLASH_UPT	(1<<2)
-#define ADIS16260_DIAG_STAT_POWER_HIGH	(1<<1)
-#define ADIS16260_DIAG_STAT_POWER_LOW	(1<<0)
+#define ADIS16260_DIAG_STAT_FLASH_CHK_BIT	6
+#define ADIS16260_DIAG_STAT_SELF_TEST_BIT	5
+#define ADIS16260_DIAG_STAT_OVERFLOW_BIT	4
+#define ADIS16260_DIAG_STAT_SPI_FAIL_BIT	3
+#define ADIS16260_DIAG_STAT_FLASH_UPT_BIT	2
+#define ADIS16260_DIAG_STAT_POWER_HIGH_BIT	1
+#define ADIS16260_DIAG_STAT_POWER_LOW_BIT	0
 
 /* GLOB_CMD */
 #define ADIS16260_GLOB_CMD_SW_RESET	(1<<7)
@@ -75,82 +72,27 @@
 #define ADIS16260_GLOB_CMD_FAC_CALIB	(1<<1)
 #define ADIS16260_GLOB_CMD_AUTO_NULL	(1<<0)
 
-#define ADIS16260_MAX_TX 24
-#define ADIS16260_MAX_RX 24
-
 #define ADIS16260_SPI_SLOW	(u32)(300 * 1000)
 #define ADIS16260_SPI_BURST	(u32)(1000 * 1000)
 #define ADIS16260_SPI_FAST	(u32)(2000 * 1000)
 
 /**
  * struct adis16260_state - device instance specific data
- * @us:			actual spi_device
- * @trig:		data ready trigger registered with iio
- * @buf_lock:		mutex to protect tx and rx
  * @negate:		negate the scale parameter
- * @tx:			transmit buffer
- * @rx:			receive buffer
  **/
 struct adis16260_state {
-	struct spi_device	*us;
-	struct iio_trigger	*trig;
-	struct mutex		buf_lock;
-	unsigned		negate:1;
-	u8			tx[ADIS16260_MAX_TX] ____cacheline_aligned;
-	u8			rx[ADIS16260_MAX_RX];
+	unsigned	negate:1;
+	struct adis	adis;
 };
 
-int adis16260_set_irq(struct iio_dev *indio_dev, bool enable);
-
 /* At the moment triggers are only used for ring buffer
  * filling. This may change!
  */
 
-#define ADIS16260_SCAN_SUPPLY	0
-#define ADIS16260_SCAN_GYRO	1
+#define ADIS16260_SCAN_GYRO	0
+#define ADIS16260_SCAN_SUPPLY	1
 #define ADIS16260_SCAN_AUX_ADC	2
 #define ADIS16260_SCAN_TEMP	3
 #define ADIS16260_SCAN_ANGL	4
 
-#ifdef CONFIG_IIO_BUFFER
-void adis16260_remove_trigger(struct iio_dev *indio_dev);
-int adis16260_probe_trigger(struct iio_dev *indio_dev);
-
-ssize_t adis16260_read_data_from_ring(struct device *dev,
-				      struct device_attribute *attr,
-				      char *buf);
-
-
-int adis16260_configure_ring(struct iio_dev *indio_dev);
-void adis16260_unconfigure_ring(struct iio_dev *indio_dev);
-
-#else /* CONFIG_IIO_BUFFER */
-
-static inline void adis16260_remove_trigger(struct iio_dev *indio_dev)
-{
-}
-
-static inline int adis16260_probe_trigger(struct iio_dev *indio_dev)
-{
-	return 0;
-}
-
-static inline ssize_t
-adis16260_read_data_from_ring(struct device *dev,
-			      struct device_attribute *attr,
-			      char *buf)
-{
-	return 0;
-}
-
-static int adis16260_configure_ring(struct iio_dev *indio_dev)
-{
-	return 0;
-}
-
-static inline void adis16260_unconfigure_ring(struct iio_dev *indio_dev)
-{
-}
-
-#endif /* CONFIG_IIO_BUFFER */
 #endif /* SPI_ADIS16260_H_ */
diff --git a/drivers/staging/iio/gyro/adis16260_core.c b/drivers/staging/iio/gyro/adis16260_core.c
index e822460..820547b 100644
--- a/drivers/staging/iio/gyro/adis16260_core.c
+++ b/drivers/staging/iio/gyro/adis16260_core.c
@@ -24,132 +24,13 @@
 
 #include "adis16260.h"
 
-static int adis16260_check_status(struct iio_dev *indio_dev);
-
-/**
- * adis16260_spi_write_reg_8() - write single byte to a register
- * @indio_dev: iio_dev for the device
- * @reg_address: the address of the register to be written
- * @val: the value to write
- **/
-static int adis16260_spi_write_reg_8(struct iio_dev *indio_dev,
-		u8 reg_address,
-		u8 val)
-{
-	int ret;
-	struct adis16260_state *st = iio_priv(indio_dev);
-
-	mutex_lock(&st->buf_lock);
-	st->tx[0] = ADIS16260_WRITE_REG(reg_address);
-	st->tx[1] = val;
-
-	ret = spi_write(st->us, st->tx, 2);
-	mutex_unlock(&st->buf_lock);
-
-	return ret;
-}
-
-/**
- * adis16260_spi_write_reg_16() - write 2 bytes to a pair of registers
- * @indio_dev: iio_dev for the device
- * @reg_address: the address of the lower of the two registers. Second register
- *               is assumed to have address one greater.
- * @val: value to be written
- **/
-static int adis16260_spi_write_reg_16(struct iio_dev *indio_dev,
-		u8 lower_reg_address,
-		u16 value)
-{
-	int ret;
-	struct spi_message msg;
-	struct adis16260_state *st = iio_priv(indio_dev);
-	struct spi_transfer xfers[] = {
-		{
-			.tx_buf = st->tx,
-			.bits_per_word = 8,
-			.len = 2,
-			.cs_change = 1,
-			.delay_usecs = 20,
-		}, {
-			.tx_buf = st->tx + 2,
-			.bits_per_word = 8,
-			.len = 2,
-			.delay_usecs = 20,
-		},
-	};
-
-	mutex_lock(&st->buf_lock);
-	st->tx[0] = ADIS16260_WRITE_REG(lower_reg_address);
-	st->tx[1] = value & 0xFF;
-	st->tx[2] = ADIS16260_WRITE_REG(lower_reg_address + 1);
-	st->tx[3] = (value >> 8) & 0xFF;
-
-	spi_message_init(&msg);
-	spi_message_add_tail(&xfers[0], &msg);
-	spi_message_add_tail(&xfers[1], &msg);
-	ret = spi_sync(st->us, &msg);
-	mutex_unlock(&st->buf_lock);
-
-	return ret;
-}
-
-/**
- * adis16260_spi_read_reg_16() - read 2 bytes from a 16-bit register
- * @indio_dev: iio_dev for the device
- * @reg_address: the address of the lower of the two registers. Second register
- *               is assumed to have address one greater.
- * @val: somewhere to pass back the value read
- **/
-static int adis16260_spi_read_reg_16(struct iio_dev *indio_dev,
-		u8 lower_reg_address,
-		u16 *val)
-{
-	struct spi_message msg;
-	struct adis16260_state *st = iio_priv(indio_dev);
-	int ret;
-	struct spi_transfer xfers[] = {
-		{
-			.tx_buf = st->tx,
-			.bits_per_word = 8,
-			.len = 2,
-			.cs_change = 1,
-			.delay_usecs = 30,
-		}, {
-			.rx_buf = st->rx,
-			.bits_per_word = 8,
-			.len = 2,
-			.delay_usecs = 30,
-		},
-	};
-
-	mutex_lock(&st->buf_lock);
-	st->tx[0] = ADIS16260_READ_REG(lower_reg_address);
-	st->tx[1] = 0;
-
-	spi_message_init(&msg);
-	spi_message_add_tail(&xfers[0], &msg);
-	spi_message_add_tail(&xfers[1], &msg);
-	ret = spi_sync(st->us, &msg);
-	if (ret) {
-		dev_err(&st->us->dev,
-			"problem when reading 16 bit register 0x%02X",
-			lower_reg_address);
-		goto error_ret;
-	}
-	*val = (st->rx[0] << 8) | st->rx[1];
-
-error_ret:
-	mutex_unlock(&st->buf_lock);
-	return ret;
-}
-
 static ssize_t adis16260_read_frequency_available(struct device *dev,
 						  struct device_attribute *attr,
 						  char *buf)
 {
 	struct iio_dev *indio_dev = dev_to_iio_dev(dev);
 	struct adis16260_state *st = iio_priv(indio_dev);
-	if (spi_get_device_id(st->us)->driver_data)
+	if (spi_get_device_id(st->adis.spi)->driver_data)
 		return sprintf(buf, "%s\n", "0.129 ~ 256");
 	else
 		return sprintf(buf, "%s\n", "256 2048");
@@ -164,13 +45,11 @@ static ssize_t adis16260_read_frequency(struct device *dev,
 	int ret, len = 0;
 	u16 t;
 	int sps;
-	ret = adis16260_spi_read_reg_16(indio_dev,
-			ADIS16260_SMPL_PRD,
-			&t);
+	ret = adis_read_reg_16(&st->adis, ADIS16260_SMPL_PRD, &t);
 	if (ret)
 		return ret;
 
-	if (spi_get_device_id(st->us)->driver_data) /* If an adis16251 */
+	if (spi_get_device_id(st->adis.spi)->driver_data) /* If an adis16251 */
 		sps =  (t & ADIS16260_SMPL_PRD_TIME_BASE) ? 8 : 256;
 	else
 		sps =  (t & ADIS16260_SMPL_PRD_TIME_BASE) ? 66 : 2048;
@@ -197,7 +76,7 @@ static ssize_t adis16260_write_frequency(struct device *dev,
 		return -EINVAL;
 
 	mutex_lock(&indio_dev->mlock);
-	if (spi_get_device_id(st->us)) {
+	if (spi_get_device_id(st->adis.spi)->driver_data) {
 		t = (256 / val);
 		if (t > 0)
 			t--;
@@ -209,10 +88,10 @@ static ssize_t adis16260_write_frequency(struct device *dev,
 		t &= ADIS16260_SMPL_PRD_DIV_MASK;
 	}
 	if ((t & ADIS16260_SMPL_PRD_DIV_MASK) >= 0x0A)
-		st->us->max_speed_hz = ADIS16260_SPI_SLOW;
+		st->adis.spi->max_speed_hz = ADIS16260_SPI_SLOW;
 	else
-		st->us->max_speed_hz = ADIS16260_SPI_FAST;
-	ret = adis16260_spi_write_reg_8(indio_dev,
+		st->adis.spi->max_speed_hz = ADIS16260_SPI_FAST;
+	ret = adis_write_reg_8(&st->adis,
 			ADIS16260_SMPL_PRD,
 			t);
 
@@ -221,140 +100,20 @@ static ssize_t adis16260_write_frequency(struct device *dev,
 	return ret ? ret : len;
 }
 
-static int adis16260_reset(struct iio_dev *indio_dev)
-{
-	int ret;
-	ret = adis16260_spi_write_reg_8(indio_dev,
-			ADIS16260_GLOB_CMD,
-			ADIS16260_GLOB_CMD_SW_RESET);
-	if (ret)
-		dev_err(&indio_dev->dev, "problem resetting device");
-
-	return ret;
-}
-
-int adis16260_set_irq(struct iio_dev *indio_dev, bool enable)
-{
-	int ret;
-	u16 msc;
-	ret = adis16260_spi_read_reg_16(indio_dev, ADIS16260_MSC_CTRL, &msc);
-	if (ret)
-		goto error_ret;
-
-	msc |= ADIS16260_MSC_CTRL_DATA_RDY_POL_HIGH;
-	if (enable)
-		msc |= ADIS16260_MSC_CTRL_DATA_RDY_EN;
-	else
-		msc &= ~ADIS16260_MSC_CTRL_DATA_RDY_EN;
-
-	ret = adis16260_spi_write_reg_16(indio_dev, ADIS16260_MSC_CTRL, msc);
-	if (ret)
-		goto error_ret;
-
-error_ret:
-	return ret;
-}
-
 /* Power down the device */
 static int adis16260_stop_device(struct iio_dev *indio_dev)
 {
+	struct adis16260_state *st = iio_priv(indio_dev);
 	int ret;
 	u16 val = ADIS16260_SLP_CNT_POWER_OFF;
 
-	ret = adis16260_spi_write_reg_16(indio_dev, ADIS16260_SLP_CNT, val);
+	ret = adis_write_reg_16(&st->adis, ADIS16260_SLP_CNT, val);
 	if (ret)
 		dev_err(&indio_dev->dev, "problem with turning device off: SLP_CNT");
 
 	return ret;
 }
 
-static int adis16260_self_test(struct iio_dev *indio_dev)
-{
-	int ret;
-	ret = adis16260_spi_write_reg_16(indio_dev,
-			ADIS16260_MSC_CTRL,
-			ADIS16260_MSC_CTRL_MEM_TEST);
-	if (ret) {
-		dev_err(&indio_dev->dev, "problem starting self test");
-		goto err_ret;
-	}
-
-	adis16260_check_status(indio_dev);
-
-err_ret:
-	return ret;
-}
-
-static int adis16260_check_status(struct iio_dev *indio_dev)
-{
-	u16 status;
-	int ret;
-	struct device *dev = &indio_dev->dev;
-
-	ret = adis16260_spi_read_reg_16(indio_dev,
-					ADIS16260_DIAG_STAT,
-					&status);
-
-	if (ret < 0) {
-		dev_err(dev, "Reading status failed\n");
-		goto error_ret;
-	}
-	ret = status & 0x7F;
-	if (status & ADIS16260_DIAG_STAT_FLASH_CHK)
-		dev_err(dev, "Flash checksum error\n");
-	if (status & ADIS16260_DIAG_STAT_SELF_TEST)
-		dev_err(dev, "Self test error\n");
-	if (status & ADIS16260_DIAG_STAT_OVERFLOW)
-		dev_err(dev, "Sensor overrange\n");
-	if (status & ADIS16260_DIAG_STAT_SPI_FAIL)
-		dev_err(dev, "SPI failure\n");
-	if (status & ADIS16260_DIAG_STAT_FLASH_UPT)
-		dev_err(dev, "Flash update failed\n");
-	if (status & ADIS16260_DIAG_STAT_POWER_HIGH)
-		dev_err(dev, "Power supply above 5.25V\n");
-	if (status & ADIS16260_DIAG_STAT_POWER_LOW)
-		dev_err(dev, "Power supply below 4.75V\n");
-
-error_ret:
-	return ret;
-}
-
-static int adis16260_initial_setup(struct iio_dev *indio_dev)
-{
-	int ret;
-	struct device *dev = &indio_dev->dev;
-
-	/* Disable IRQ */
-	ret = adis16260_set_irq(indio_dev, false);
-	if (ret) {
-		dev_err(dev, "disable irq failed");
-		goto err_ret;
-	}
-
-	/* Do self test */
-	ret = adis16260_self_test(indio_dev);
-	if (ret) {
-		dev_err(dev, "self test failure");
-		goto err_ret;
-	}
-
-	/* Read status register to check the result */
-	ret = adis16260_check_status(indio_dev);
-	if (ret) {
-		adis16260_reset(indio_dev);
-		dev_err(dev, "device not playing ball -> reset");
-		msleep(ADIS16260_STARTUP_DELAY);
-		ret = adis16260_check_status(indio_dev);
-		if (ret) {
-			dev_err(dev, "giving up");
-			goto err_ret;
-		}
-	}
-
-err_ret:
-	return ret;
-}
-
 static IIO_DEV_ATTR_SAMP_FREQ(S_IWUSR | S_IRUGO,
 		adis16260_read_frequency,
 		adis16260_write_frequency);
@@ -362,100 +121,26 @@ static IIO_DEV_ATTR_SAMP_FREQ(S_IWUSR | S_IRUGO,
 static IIO_DEVICE_ATTR(sampling_frequency_available,
 		       S_IRUGO, adis16260_read_frequency_available, NULL, 0);
 
-enum adis16260_channel {
-	gyro,
-	temp,
-	in_supply,
-	in_aux,
-	angle,
-};
 #define ADIS16260_GYRO_CHANNEL_SET(axis, mod)				\
-	struct iio_chan_spec adis16260_channels_##axis[] = {		\
-		{							\
-			.type = IIO_ANGL_VEL,				\
-			.modified = 1,					\
-			.channel2 = mod,				\
-			.info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT |	\
-			IIO_CHAN_INFO_CALIBBIAS_SEPARATE_BIT |		\
-			IIO_CHAN_INFO_CALIBSCALE_SEPARATE_BIT |		\
-			IIO_CHAN_INFO_SCALE_SEPARATE_BIT,		\
-			.address = gyro,				\
-			.scan_index = ADIS16260_SCAN_GYRO,		\
-			.scan_type = {					\
-				.sign = 's',				\
-				.realbits = 14,				\
-				.storagebits = 16,			\
-			},						\
-		}, {							\
-			.type = IIO_ANGL,				\
-			.modified = 1,					\
-			.channel2 = mod,				\
-			.info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT,	\
-			.address = angle,				\
-			.scan_index = ADIS16260_SCAN_ANGL,		\
-			.scan_type = {					\
-				.sign = 'u',				\
-				.realbits = 14,				\
-				.storagebits = 16,			\
-			},						\
-		}, {							\
-			.type = IIO_TEMP,				\
-			.indexed = 1,					\
-			.channel = 0,					\
-			.info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT |	\
-			IIO_CHAN_INFO_OFFSET_SEPARATE_BIT |		\
-			IIO_CHAN_INFO_SCALE_SEPARATE_BIT,		\
-			.address = temp,				\
-			.scan_index = ADIS16260_SCAN_TEMP,		\
-			.scan_type = {					\
-				.sign = 'u',				\
-				.realbits = 12,				\
-				.storagebits = 16,			\
-			},						\
-		}, {							\
-			.type = IIO_VOLTAGE,				\
-			.indexed = 1,					\
-			.channel = 0,					\
-			.extend_name = "supply",			\
-			.info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT |	\
-			IIO_CHAN_INFO_SCALE_SEPARATE_BIT,		\
-			.address = in_supply,				\
-			.scan_index = ADIS16260_SCAN_SUPPLY,		\
-			.scan_type = {					\
-				.sign = 'u',				\
-				.realbits = 12,				\
-				.storagebits = 16,			\
-			},						\
-		}, {							\
-			.type = IIO_VOLTAGE,				\
-			.indexed = 1,					\
-			.channel = 1,					\
-			.info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT |	\
-			IIO_CHAN_INFO_SCALE_SEPARATE_BIT,		\
-			.address = in_aux,				\
-			.scan_index = ADIS16260_SCAN_AUX_ADC,		\
-			.scan_type = {					\
-				.sign = 'u',				\
-				.realbits = 12,				\
-				.storagebits = 16,			\
-			},						\
-		},							\
-		IIO_CHAN_SOFT_TIMESTAMP(5),				\
-	}
+struct iio_chan_spec adis16260_channels_##axis[] = {		\
+	ADIS_GYRO_CHAN(mod, ADIS16260_GYRO_OUT, ADIS16260_SCAN_GYRO, \
+		IIO_CHAN_INFO_CALIBBIAS_SEPARATE_BIT | \
+		IIO_CHAN_INFO_CALIBSCALE_SEPARATE_BIT, 14), \
+	ADIS_INCLI_CHAN(mod, ADIS16260_ANGL_OUT, ADIS16260_SCAN_ANGL, 0, 14), \
+	ADIS_TEMP_CHAN(ADIS16260_TEMP_OUT, ADIS16260_SCAN_TEMP, 12), \
+	ADIS_SUPPLY_CHAN(ADIS16260_SUPPLY_OUT, ADIS16260_SCAN_SUPPLY, 12), \
+	ADIS_AUX_ADC_CHAN(ADIS16260_AUX_ADC, ADIS16260_SCAN_AUX_ADC, 12), \
+	IIO_CHAN_SOFT_TIMESTAMP(5),				\
+}
 
-static const ADIS16260_GYRO_CHANNEL_SET(x, IIO_MOD_X);
-static const ADIS16260_GYRO_CHANNEL_SET(y, IIO_MOD_Y);
-static const ADIS16260_GYRO_CHANNEL_SET(z, IIO_MOD_Z);
-
-static const u8 adis16260_addresses[5][3] = {
-	[gyro] = { ADIS16260_GYRO_OUT,
-		   ADIS16260_GYRO_OFF,
-		   ADIS16260_GYRO_SCALE },
-	[angle] = { ADIS16260_ANGL_OUT },
-	[in_supply] = { ADIS16260_SUPPLY_OUT },
-	[in_aux] = { ADIS16260_AUX_ADC },
-	[temp] = { ADIS16260_TEMP_OUT },
+static const ADIS16260_GYRO_CHANNEL_SET(x, X);
+static const ADIS16260_GYRO_CHANNEL_SET(y, Y);
+static const ADIS16260_GYRO_CHANNEL_SET(z, Z);
+
+static const u8 adis16260_addresses[][2] = {
+	[ADIS16260_SCAN_GYRO] = { ADIS16260_GYRO_OFF, ADIS16260_GYRO_SCALE },
 };
+
 static int adis16260_read_raw(struct iio_dev *indio_dev,
 			      struct iio_chan_spec const *chan,
 			      int *val, int *val2,
@@ -469,34 +154,13 @@ static int adis16260_read_raw(struct iio_dev *indio_dev,
 
 	switch (mask) {
 	case IIO_CHAN_INFO_RAW:
-		mutex_lock(&indio_dev->mlock);
-		addr = adis16260_addresses[chan->address][0];
-		ret = adis16260_spi_read_reg_16(indio_dev, addr, &val16);
-		if (ret) {
-			mutex_unlock(&indio_dev->mlock);
-			return ret;
-		}
-
-		if (val16 & ADIS16260_ERROR_ACTIVE) {
-			ret = adis16260_check_status(indio_dev);
-			if (ret) {
-				mutex_unlock(&indio_dev->mlock);
-				return ret;
-			}
-		}
-		val16 = val16 & ((1 << chan->scan_type.realbits) - 1);
-		if (chan->scan_type.sign == 's')
-			val16 = (s16)(val16 <<
-				      (16 - chan->scan_type.realbits)) >>
-				(16 - chan->scan_type.realbits);
-		*val = val16;
-		mutex_unlock(&indio_dev->mlock);
-		return IIO_VAL_INT;
+		return adis_single_conversion(indio_dev, chan,
+				ADIS16260_ERROR_ACTIVE, val);
 	case IIO_CHAN_INFO_SCALE:
 		switch (chan->type) {
 		case IIO_ANGL_VEL:
 			*val = 0;
-			if (spi_get_device_id(st->us)->driver_data) {
+			if (spi_get_device_id(st->adis.spi)->driver_data) {
 				/* 0.01832 degree / sec */
 				*val2 = IIO_DEGREE_TO_RAD(18320);
 			} else {
@@ -533,8 +197,8 @@ static int adis16260_read_raw(struct iio_dev *indio_dev,
 			return -EINVAL;
 		}
 		mutex_lock(&indio_dev->mlock);
-		addr = adis16260_addresses[chan->address][1];
-		ret = adis16260_spi_read_reg_16(indio_dev, addr, &val16);
+		addr = adis16260_addresses[chan->scan_index][0];
+		ret = adis_read_reg_16(&st->adis, addr, &val16);
 		if (ret) {
 			mutex_unlock(&indio_dev->mlock);
 			return ret;
@@ -553,8 +217,8 @@ static int adis16260_read_raw(struct iio_dev *indio_dev,
 			return -EINVAL;
 		}
 		mutex_lock(&indio_dev->mlock);
-		addr = adis16260_addresses[chan->address][2];
-		ret = adis16260_spi_read_reg_16(indio_dev, addr, &val16);
+		addr = adis16260_addresses[chan->scan_index][1];
+		ret = adis_read_reg_16(&st->adis, addr, &val16);
 		if (ret) {
 			mutex_unlock(&indio_dev->mlock);
 			return ret;
@@ -572,18 +236,19 @@ static int adis16260_write_raw(struct iio_dev *indio_dev,
 			       int val2,
 			       long mask)
 {
+	struct adis16260_state *st = iio_priv(indio_dev);
 	int bits = 12;
 	s16 val16;
 	u8 addr;
 	switch (mask) {
 	case IIO_CHAN_INFO_CALIBBIAS:
 		val16 = val & ((1 << bits) - 1);
-		addr = adis16260_addresses[chan->address][1];
-		return adis16260_spi_write_reg_16(indio_dev, addr, val16);
+		addr = adis16260_addresses[chan->scan_index][0];
+		return adis_write_reg_16(&st->adis, addr, val16);
 	case IIO_CHAN_INFO_CALIBSCALE:
 		val16 = val & ((1 << bits) - 1);
-		addr = adis16260_addresses[chan->address][2];
-		return adis16260_spi_write_reg_16(indio_dev, addr, val16);
+		addr = adis16260_addresses[chan->scan_index][1];
+		return adis_write_reg_16(&st->adis, addr, val16);
 	}
 	return -EINVAL;
 }
@@ -605,6 +270,36 @@ static const struct iio_info adis16260_info = {
 	.driver_module = THIS_MODULE,
 };
 
+static const char * const adis1620_status_error_msgs[] = {
+	[ADIS16260_DIAG_STAT_FLASH_CHK_BIT] = "Flash checksum error",
+	[ADIS16260_DIAG_STAT_SELF_TEST_BIT] = "Self test error",
+	[ADIS16260_DIAG_STAT_OVERFLOW_BIT] = "Sensor overrange",
+	[ADIS16260_DIAG_STAT_SPI_FAIL_BIT] = "SPI failure",
+	[ADIS16260_DIAG_STAT_FLASH_UPT_BIT] = "Flash update failed",
+	[ADIS16260_DIAG_STAT_POWER_HIGH_BIT] = "Power supply above 5.25",
+	[ADIS16260_DIAG_STAT_POWER_LOW_BIT] = "Power supply below 4.75",
+};
+
+static const struct adis_data adis16260_data = {
+	.write_delay = 30,
+	.read_delay = 30,
+	.msc_ctrl_reg = ADIS16260_MSC_CTRL,
+	.glob_cmd_reg = ADIS16260_GLOB_CMD,
+	.diag_stat_reg = ADIS16260_DIAG_STAT,
+
+	.self_test_mask = ADIS16260_MSC_CTRL_MEM_TEST,
+	.startup_delay = ADIS16260_STARTUP_DELAY,
+
+	.status_error_msgs = adis1620_status_error_msgs,
+	.status_error_mask = BIT(ADIS16260_DIAG_STAT_FLASH_CHK_BIT) |
+		BIT(ADIS16260_DIAG_STAT_SELF_TEST_BIT) |
+		BIT(ADIS16260_DIAG_STAT_OVERFLOW_BIT) |
+		BIT(ADIS16260_DIAG_STAT_SPI_FAIL_BIT) |
+		BIT(ADIS16260_DIAG_STAT_FLASH_UPT_BIT) |
+		BIT(ADIS16260_DIAG_STAT_POWER_HIGH_BIT) |
+		BIT(ADIS16260_DIAG_STAT_POWER_LOW_BIT),
+};
+
 static int __devinit adis16260_probe(struct spi_device *spi)
 {
 	int ret;
@@ -624,10 +319,7 @@ static int __devinit adis16260_probe(struct spi_device *spi)
 	/* this is only used for removal purposes */
 	spi_set_drvdata(spi, indio_dev);
 
-	st->us = spi;
-	mutex_init(&st->buf_lock);
-
-	indio_dev->name = spi_get_device_id(st->us)->name;
+	indio_dev->name = spi_get_device_id(spi)->name;
 	indio_dev->dev.parent = &spi->dev;
 	indio_dev->info = &adis16260_info;
 	indio_dev->num_channels
@@ -651,17 +343,14 @@ static int __devinit adis16260_probe(struct spi_device *spi)
 	indio_dev->num_channels = ARRAY_SIZE(adis16260_channels_x);
 	indio_dev->modes = INDIO_DIRECT_MODE;
 
-	ret = adis16260_configure_ring(indio_dev);
+	ret = adis_init(&st->adis, indio_dev, spi, &adis16260_data);
+	if (ret)
+		goto error_free_dev;
+
+	ret = adis_setup_buffer_and_trigger(&st->adis, indio_dev, NULL);
 	if (ret)
 		goto error_free_dev;
 
-	ret = iio_buffer_register(indio_dev,
-				  indio_dev->channels,
-				  ARRAY_SIZE(adis16260_channels_x));
-	if (ret) {
-		printk(KERN_ERR "failed to initialize the ring\n");
-		goto error_unreg_ring_funcs;
-	}
 	if (indio_dev->buffer) {
 		/* Set default scan mode */
 		iio_scan_mask_set(indio_dev, indio_dev->buffer,
@@ -675,28 +364,19 @@ static int __devinit adis16260_probe(struct spi_device *spi)
 		iio_scan_mask_set(indio_dev, indio_dev->buffer,
 				  ADIS16260_SCAN_ANGL);
 	}
-	if (spi->irq) {
-		ret = adis16260_probe_trigger(indio_dev);
-		if (ret)
-			goto error_uninitialize_ring;
-	}
 
 	/* Get the device into a sane initial state */
-	ret = adis16260_initial_setup(indio_dev);
+	ret = adis_initial_startup(&st->adis);
 	if (ret)
-		goto error_remove_trigger;
+		goto error_cleanup_buffer_trigger;
 	ret = iio_device_register(indio_dev);
 	if (ret)
-		goto error_remove_trigger;
+		goto error_cleanup_buffer_trigger;
 
 	return 0;
 
-error_remove_trigger:
-	adis16260_remove_trigger(indio_dev);
-error_uninitialize_ring:
-	iio_buffer_unregister(indio_dev);
-error_unreg_ring_funcs:
-	adis16260_unconfigure_ring(indio_dev);
+error_cleanup_buffer_trigger:
+	adis_cleanup_buffer_and_trigger(&st->adis, indio_dev);
 error_free_dev:
 	iio_device_free(indio_dev);
 error_ret:
@@ -706,12 +386,11 @@ error_ret:
 static int __devexit adis16260_remove(struct spi_device *spi)
 {
 	struct iio_dev *indio_dev = spi_get_drvdata(spi);
+	struct adis16260_state *st = iio_priv(indio_dev);
 
 	iio_device_unregister(indio_dev);
 	adis16260_stop_device(indio_dev);
-	adis16260_remove_trigger(indio_dev);
-	iio_buffer_unregister(indio_dev);
-	adis16260_unconfigure_ring(indio_dev);
+	adis_cleanup_buffer_and_trigger(&st->adis, indio_dev);
 	iio_device_free(indio_dev);
 
 	return 0;
diff --git a/drivers/staging/iio/gyro/adis16260_ring.c b/drivers/staging/iio/gyro/adis16260_ring.c
deleted file mode 100644
index d6c48f8..0000000
--- a/drivers/staging/iio/gyro/adis16260_ring.c
+++ /dev/null
@@ -1,136 +0,0 @@
-#include <linux/export.h>
-#include <linux/interrupt.h>
-#include <linux/mutex.h>
-#include <linux/kernel.h>
-#include <linux/spi/spi.h>
-#include <linux/slab.h>
-
-#include <linux/iio/iio.h>
-#include "../ring_sw.h"
-#include <linux/iio/trigger_consumer.h>
-#include "adis16260.h"
-
-/**
- * adis16260_read_ring_data() read data registers which will be placed into ring
- * @indio_dev: the IIO device
- * @rx: somewhere to pass back the value read
- **/
-static int adis16260_read_ring_data(struct iio_dev *indio_dev, u8 *rx)
-{
-	struct spi_message msg;
-	struct adis16260_state *st = iio_priv(indio_dev);
-	struct spi_transfer xfers[ADIS16260_OUTPUTS + 1];
-	int ret;
-	int i;
-
-	mutex_lock(&st->buf_lock);
-
-	spi_message_init(&msg);
-
-	memset(xfers, 0, sizeof(xfers));
-	for (i = 0; i <= ADIS16260_OUTPUTS; i++) {
-		xfers[i].bits_per_word = 8;
-		xfers[i].cs_change = 1;
-		xfers[i].len = 2;
-		xfers[i].delay_usecs = 30;
-		xfers[i].tx_buf = st->tx + 2 * i;
-		if (i < 2) /* SUPPLY_OUT:0x02 GYRO_OUT:0x04 */
-			st->tx[2 * i]
-				= ADIS16260_READ_REG(ADIS16260_SUPPLY_OUT
-						+ 2 * i);
-		else /* 0x06 to 0x09 is reserved */
-			st->tx[2 * i]
-				= ADIS16260_READ_REG(ADIS16260_SUPPLY_OUT
-						+ 2 * i + 4);
-		st->tx[2 * i + 1] = 0;
-		if (i >= 1)
-			xfers[i].rx_buf = rx + 2 * (i - 1);
-		spi_message_add_tail(&xfers[i], &msg);
-	}
-
-	ret = spi_sync(st->us, &msg);
-	if (ret)
-		dev_err(&st->us->dev, "problem when burst reading");
-
-	mutex_unlock(&st->buf_lock);
-
-	return ret;
-}
-
-static irqreturn_t adis16260_trigger_handler(int irq, void *p)
-{
-	struct iio_poll_func *pf = p;
-	struct iio_dev *indio_dev = pf->indio_dev;
-	struct adis16260_state *st = iio_priv(indio_dev);
-	int i = 0;
-	s16 *data;
-
-	data = kmalloc(indio_dev->scan_bytes, GFP_KERNEL);
-	if (data == NULL) {
-		dev_err(&st->us->dev, "memory alloc failed in ring bh");
-		goto done;
-	}
-
-	if (!bitmap_empty(indio_dev->active_scan_mask, indio_dev->masklength) &&
-	    adis16260_read_ring_data(indio_dev, st->rx) >= 0)
-		for (; i < bitmap_weight(indio_dev->active_scan_mask,
-					 indio_dev->masklength); i++)
-			data[i] = be16_to_cpup((__be16 *)&(st->rx[i*2]));
-
-	/* Guaranteed to be aligned with 8 byte boundary */
-	if (indio_dev->scan_timestamp)
-		*((s64 *)(data + ((i + 3)/4)*4)) = pf->timestamp;
-
-	iio_push_to_buffers(indio_dev, (u8 *)data);
-
-	kfree(data);
-done:
-	iio_trigger_notify_done(indio_dev->trig);
-
-	return IRQ_HANDLED;
-}
-
-void adis16260_unconfigure_ring(struct iio_dev *indio_dev)
-{
-	iio_dealloc_pollfunc(indio_dev->pollfunc);
-	iio_sw_rb_free(indio_dev->buffer);
-}
-
-static const struct iio_buffer_setup_ops adis16260_ring_setup_ops = {
-	.preenable = &iio_sw_buffer_preenable,
-	.postenable = &iio_triggered_buffer_postenable,
-	.predisable = &iio_triggered_buffer_predisable,
-};
-
-int adis16260_configure_ring(struct iio_dev *indio_dev)
-{
-	int ret = 0;
-	struct iio_buffer *ring;
-
-	ring = iio_sw_rb_allocate(indio_dev);
-	if (!ring) {
-		ret = -ENOMEM;
-		return ret;
-	}
-	indio_dev->buffer = ring;
-	ring->scan_timestamp = true;
-	indio_dev->setup_ops = &adis16260_ring_setup_ops;
-
-	indio_dev->pollfunc = iio_alloc_pollfunc(&iio_pollfunc_store_time,
-						 &adis16260_trigger_handler,
-						 IRQF_ONESHOT,
-						 indio_dev,
-						 "adis16260_consumer%d",
-						 indio_dev->id);
-	if (indio_dev->pollfunc == NULL) {
-		ret = -ENOMEM;
-		goto error_iio_sw_rb_free;
-	}
-
-	indio_dev->modes |= INDIO_BUFFER_TRIGGERED;
-	return 0;
-
-error_iio_sw_rb_free:
-	iio_sw_rb_free(indio_dev->buffer);
-	return ret;
-}
diff --git a/drivers/staging/iio/gyro/adis16260_trigger.c b/drivers/staging/iio/gyro/adis16260_trigger.c
deleted file mode 100644
index 034559e..0000000
--- a/drivers/staging/iio/gyro/adis16260_trigger.c
+++ /dev/null
@@ -1,75 +0,0 @@
-#include <linux/interrupt.h>
-#include <linux/kernel.h>
-#include <linux/spi/spi.h>
-#include <linux/export.h>
-
-#include <linux/iio/iio.h>
-#include <linux/iio/trigger.h>
-#include "adis16260.h"
-
-/**
- * adis16260_data_rdy_trigger_set_state() set datardy interrupt state
- **/
-static int adis16260_data_rdy_trigger_set_state(struct iio_trigger *trig,
-						bool state)
-{
-	struct iio_dev *indio_dev = trig->private_data;
-
-	dev_dbg(&indio_dev->dev, "%s (%d)\n", __func__, state);
-	return adis16260_set_irq(indio_dev, state);
-}
-
-static const struct iio_trigger_ops adis16260_trigger_ops = {
-	.owner = THIS_MODULE,
-	.set_trigger_state = &adis16260_data_rdy_trigger_set_state,
-};
-
-int adis16260_probe_trigger(struct iio_dev *indio_dev)
-{
-	int ret;
-	struct adis16260_state *st = iio_priv(indio_dev);
-
-	st->trig = iio_trigger_alloc("%s-dev%d",
-					spi_get_device_id(st->us)->name,
-					indio_dev->id);
-	if (st->trig == NULL) {
-		ret = -ENOMEM;
-		goto error_ret;
-	}
-
-	ret = request_irq(st->us->irq,
-			  &iio_trigger_generic_data_rdy_poll,
-			  IRQF_TRIGGER_RISING,
-			  "adis16260",
-			  st->trig);
-	if (ret)
-		goto error_free_trig;
-
-	st->trig->dev.parent = &st->us->dev;
-	st->trig->ops = &adis16260_trigger_ops;
-	st->trig->private_data = indio_dev;
-	ret = iio_trigger_register(st->trig);
-
-	/* select default trigger */
-	indio_dev->trig = st->trig;
-	if (ret)
-		goto error_free_irq;
-
-	return 0;
-
-error_free_irq:
-	free_irq(st->us->irq, st->trig);
-error_free_trig:
-	iio_trigger_free(st->trig);
-error_ret:
-	return ret;
-}
-
-void adis16260_remove_trigger(struct iio_dev *indio_dev)
-{
-	struct adis16260_state *st = iio_priv(indio_dev);
-
-	iio_trigger_unregister(st->trig);
-	free_irq(st->us->irq, st->trig);
-	iio_trigger_free(st->trig);
-}
-- 
1.8.0

--
To unsubscribe from this list: send the line "unsubscribe linux-iio" in
the body of a message to majordomo@xxxxxxxxxxxxxxx
More majordomo info at  http://vger.kernel.org/majordomo-info.html


[Index of Archives]     [Linux USB Devel]     [Video for Linux]     [Linux Audio Users]     [Yosemite News]     [Linux Input]     [Linux Kernel]     [Linux SCSI]     [X.org]

  Powered by Linux