[PATCH] iio: adc: New driver for AD7280A Lithium Ion Battery Monitoring System

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

 



From: Michael Hennerich <michael.hennerich@xxxxxxxxxx>

The AD7280A monitoring system contains all the functions required for
general purpose monitoring and maintenance of stacked
lithium ion batteries as used in hybrid electric vehicles,
battery backup applications, etc.

Changes since V1:

Make cell channels all type IIO_IN_DIFF, update documentation accordingly.
Remove unused and redundant defines.
Use SI units where applicable.
Remove unnecessary wrapper function.
Remove redundant initialization.
Add comments where requested.
Revise event handler.
Use const where applicable.

Reviewed-by: Jonathan Cameron <jic23@xxxxxxxxx>
Signed-off-by: Michael Hennerich <michael.hennerich@xxxxxxxxxx>
---
 .../iio/Documentation/sysfs-bus-iio-adc-ad7280a    |   21 +
 drivers/staging/iio/adc/Kconfig                    |   10 +
 drivers/staging/iio/adc/Makefile                   |    1 +
 drivers/staging/iio/adc/ad7280a.c                  |  993 ++++++++++++++++++++
 drivers/staging/iio/adc/ad7280a.h                  |   38 +
 5 files changed, 1063 insertions(+), 0 deletions(-)
 create mode 100644 drivers/staging/iio/Documentation/sysfs-bus-iio-adc-ad7280a
 create mode 100644 drivers/staging/iio/adc/ad7280a.c
 create mode 100644 drivers/staging/iio/adc/ad7280a.h

diff --git a/drivers/staging/iio/Documentation/sysfs-bus-iio-adc-ad7280a b/drivers/staging/iio/Documentation/sysfs-bus-iio-adc-ad7280a
new file mode 100644
index 0000000..863d385
--- /dev/null
+++ b/drivers/staging/iio/Documentation/sysfs-bus-iio-adc-ad7280a
@@ -0,0 +1,21 @@
+What:		/sys/bus/iio/devices/deviceX/inY-inZ_balance_switch_en
+KernelVersion:	3.0.0
+Contact:	linux-iio@xxxxxxxxxxxxxxx
+Description:
+		Writing 1 enables the cell balance output switch corresponding
+		to input Y. Writing 0 disables it. If the inY-inZ_balance_timer
+		is set to a none zero value, the corresponding switch will
+		enable for the programmed amount of time, before it
+		automatically disables.
+
+What:		/sys/bus/iio/devices/deviceX/inY-inZ_balance_timer
+KernelVersion:	3.0.0
+Contact:	linux-iio@xxxxxxxxxxxxxxx
+Description:
+		The inY-inZ_balance_timer file allows the user to program
+		individual times for each cell balance output. The AD7280A
+		allows the user to set the timer to a value from 0 minutes to
+		36.9 minutes. The resolution of the timer is 71.5 sec.
+		The value written is the on-time in milliseconds. When the
+		timer value is set 0, the timer is disabled. The cell balance
+		outputs are controlled only by inY-inZ_balance_switch_en.
diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
index b39f2e1..60de7d7 100644
--- a/drivers/staging/iio/adc/Kconfig
+++ b/drivers/staging/iio/adc/Kconfig
@@ -182,6 +182,16 @@ config ADT7410
 	  Say yes here to build support for Analog Devices ADT7410
 	  temperature sensors.
 
+config AD7280
+	tristate "Analog Devices AD7280A Lithium Ion Battery Monitoring System"
+	depends on SPI
+	help
+	  Say yes here to build support for Analog Devices AD7280A
+	  Lithium Ion Battery Monitoring System.
+
+	  To compile this driver as a module, choose M here: the
+	  module will be called ad7280a
+
 config MAX1363
 	tristate "Maxim max1363 ADC driver"
 	depends on I2C
diff --git a/drivers/staging/iio/adc/Makefile b/drivers/staging/iio/adc/Makefile
index f020351..634a55f 100644
--- a/drivers/staging/iio/adc/Makefile
+++ b/drivers/staging/iio/adc/Makefile
@@ -40,3 +40,4 @@ obj-$(CONFIG_AD7816) += ad7816.o
 obj-$(CONFIG_ADT75) += adt75.o
 obj-$(CONFIG_ADT7310) += adt7310.o
 obj-$(CONFIG_ADT7410) += adt7410.o
+obj-$(CONFIG_AD7280) += ad7280a.o
diff --git a/drivers/staging/iio/adc/ad7280a.c b/drivers/staging/iio/adc/ad7280a.c
new file mode 100644
index 0000000..895b1f4
--- /dev/null
+++ b/drivers/staging/iio/adc/ad7280a.c
@@ -0,0 +1,993 @@
+/*
+ * AD7280A Lithium Ion Battery Monitoring System
+ *
+ * Copyright 2011 Analog Devices Inc.
+ *
+ * Licensed under the GPL-2.
+ */
+
+#include <linux/device.h>
+#include <linux/kernel.h>
+#include <linux/slab.h>
+#include <linux/sysfs.h>
+#include <linux/spi/spi.h>
+#include <linux/err.h>
+#include <linux/delay.h>
+#include <linux/interrupt.h>
+
+#include "../iio.h"
+#include "../sysfs.h"
+#include "adc.h"
+
+#include "ad7280a.h"
+
+/* Registers */
+#define AD7280A_CELL_VOLTAGE_1		0x0  /* D11 to D0, Read only */
+#define AD7280A_CELL_VOLTAGE_2		0x1  /* D11 to D0, Read only */
+#define AD7280A_CELL_VOLTAGE_3		0x2  /* D11 to D0, Read only */
+#define AD7280A_CELL_VOLTAGE_4		0x3  /* D11 to D0, Read only */
+#define AD7280A_CELL_VOLTAGE_5		0x4  /* D11 to D0, Read only */
+#define AD7280A_CELL_VOLTAGE_6		0x5  /* D11 to D0, Read only */
+#define AD7280A_AUX_ADC_1		0x6  /* D11 to D0, Read only */
+#define AD7280A_AUX_ADC_2		0x7  /* D11 to D0, Read only */
+#define AD7280A_AUX_ADC_3		0x8  /* D11 to D0, Read only */
+#define AD7280A_AUX_ADC_4		0x9  /* D11 to D0, Read only */
+#define AD7280A_AUX_ADC_5		0xA  /* D11 to D0, Read only */
+#define AD7280A_AUX_ADC_6		0xB  /* D11 to D0, Read only */
+#define AD7280A_SELF_TEST		0xC  /* D11 to D0, Read only */
+#define AD7280A_CONTROL_HB		0xD  /* D15 to D8, Read/write */
+#define AD7280A_CONTROL_LB		0xE  /* D7 to D0, Read/write */
+#define AD7280A_CELL_OVERVOLTAGE	0xF  /* D7 to D0, Read/write */
+#define AD7280A_CELL_UNDERVOLTAGE	0x10 /* D7 to D0, Read/write */
+#define AD7280A_AUX_ADC_OVERVOLTAGE	0x11 /* D7 to D0, Read/write */
+#define AD7280A_AUX_ADC_UNDERVOLTAGE	0x12 /* D7 to D0, Read/write */
+#define AD7280A_ALERT			0x13 /* D7 to D0, Read/write */
+#define AD7280A_CELL_BALANCE		0x14 /* D7 to D0, Read/write */
+#define AD7280A_CB1_TIMER		0x15 /* D7 to D0, Read/write */
+#define AD7280A_CB2_TIMER		0x16 /* D7 to D0, Read/write */
+#define AD7280A_CB3_TIMER		0x17 /* D7 to D0, Read/write */
+#define AD7280A_CB4_TIMER		0x18 /* D7 to D0, Read/write */
+#define AD7280A_CB5_TIMER		0x19 /* D7 to D0, Read/write */
+#define AD7280A_CB6_TIMER		0x1A /* D7 to D0, Read/write */
+#define AD7280A_PD_TIMER		0x1B /* D7 to D0, Read/write */
+#define AD7280A_READ			0x1C /* D7 to D0, Read/write */
+#define AD7280A_CNVST_CONTROL		0x1D /* D7 to D0, Read/write */
+
+/* Bits and Masks */
+#define AD7280A_CTRL_HB_CONV_INPUT_ALL			(0 << 6)
+#define AD7280A_CTRL_HB_CONV_INPUT_6CELL_AUX1_3_4	(1 << 6)
+#define AD7280A_CTRL_HB_CONV_INPUT_6CELL		(2 << 6)
+#define AD7280A_CTRL_HB_CONV_INPUT_SELF_TEST		(3 << 6)
+#define AD7280A_CTRL_HB_CONV_RES_READ_ALL		(0 << 4)
+#define AD7280A_CTRL_HB_CONV_RES_READ_6CELL_AUX1_3_4	(1 << 4)
+#define AD7280A_CTRL_HB_CONV_RES_READ_6CELL		(2 << 4)
+#define AD7280A_CTRL_HB_CONV_RES_READ_NO		(3 << 4)
+#define AD7280A_CTRL_HB_CONV_START_CNVST		(0 << 3)
+#define AD7280A_CTRL_HB_CONV_START_CS			(1 << 3)
+#define AD7280A_CTRL_HB_CONV_AVG_DIS			(0 << 1)
+#define AD7280A_CTRL_HB_CONV_AVG_2			(1 << 1)
+#define AD7280A_CTRL_HB_CONV_AVG_4			(2 << 1)
+#define AD7280A_CTRL_HB_CONV_AVG_8			(3 << 1)
+#define AD7280A_CTRL_HB_CONV_AVG(x)			((x) << 1)
+#define AD7280A_CTRL_HB_PWRDN_SW			(1 << 0)
+
+#define AD7280A_CTRL_LB_SWRST				(1 << 7)
+#define AD7280A_CTRL_LB_ACQ_TIME_400ns			(0 << 5)
+#define AD7280A_CTRL_LB_ACQ_TIME_800ns			(1 << 5)
+#define AD7280A_CTRL_LB_ACQ_TIME_1200ns			(2 << 5)
+#define AD7280A_CTRL_LB_ACQ_TIME_1600ns			(3 << 5)
+#define AD7280A_CTRL_LB_ACQ_TIME(x)			((x) << 5)
+#define AD7280A_CTRL_LB_MUST_SET			(1 << 4)
+#define AD7280A_CTRL_LB_THERMISTOR_EN			(1 << 3)
+#define AD7280A_CTRL_LB_LOCK_DEV_ADDR			(1 << 2)
+#define AD7280A_CTRL_LB_INC_DEV_ADDR			(1 << 1)
+#define AD7280A_CTRL_LB_DAISY_CHAIN_RB_EN		(1 << 0)
+
+#define AD7280A_ALERT_GEN_STATIC_HIGH			(1 << 6)
+#define AD7280A_ALERT_RELAY_SIG_CHAIN_DOWN		(3 << 6)
+
+#define AD7280A_ALL_CELLS				(0xAD << 16)
+
+#define AD7280A_MAX_SPI_CLK_Hz		700000 /* < 1MHz */
+#define AD7280A_MAX_CHAIN		8
+#define AD7280A_CELLS_PER_DEV		6
+#define AD7280A_BITS			12
+#define AD7280A_NUM_CH			(AD7280A_AUX_ADC_6 - \
+					AD7280A_CELL_VOLTAGE_1 + 1)
+
+#define AD7280A_DEVADDR_MASTER		0
+#define AD7280A_DEVADDR_ALL		0x1F
+/* 5-bit device address is sent LSB first */
+#define AD7280A_DEVADDR(addr)	(((addr & 0x1) << 4) | ((addr & 0x2) << 3) | \
+				(addr & 0x4) | ((addr & 0x8) >> 3) | \
+				((addr & 0x10) >> 4))
+
+/* During a read a valid write is mandatory.
+ * So writing to the highest available address (Address 0x1F)
+ * and setting the address all parts bit to 0 is recommended
+ * So the TXVAL is AD7280A_DEVADDR_ALL + CRC
+ */
+#define AD7280A_READ_TXVAL	0xF800030A
+
+/*
+ * AD7280 CRC
+ *
+ * P(x) = x^8 + x^5 + x^3 + x^2 + x^1 + x^0 = 0b100101111 => 0x2F
+ */
+#define POLYNOM		0x2F
+#define POLYNOM_ORDER	8
+#define HIGHBIT		1 << (POLYNOM_ORDER - 1);
+
+struct ad7280_state {
+	struct spi_device		*spi;
+	struct iio_chan_spec		*channels;
+	struct iio_dev_attr		*iio_attr;
+	int				slave_num;
+	int				scan_cnt;
+	int				readback_delay_us;
+	unsigned char			crc_tab[256];
+	unsigned char			ctrl_hb;
+	unsigned char			ctrl_lb;
+	unsigned char			cell_threshhigh;
+	unsigned char			cell_threshlow;
+	unsigned char			aux_threshhigh;
+	unsigned char			aux_threshlow;
+	unsigned char			cb_mask[AD7280A_MAX_CHAIN];
+};
+
+static void ad7280_crc8_build_table(unsigned char *crc_tab)
+{
+	unsigned char bit, crc;
+	int cnt, i;
+
+	for (cnt = 0; cnt < 256; cnt++) {
+		crc = cnt;
+		for (i = 0; i < 8; i++) {
+			bit = crc & HIGHBIT;
+			crc <<= 1;
+			if (bit)
+				crc ^= POLYNOM;
+		}
+		crc_tab[cnt] = crc;
+	}
+}
+
+static unsigned char ad7280_calc_crc8(unsigned char *crc_tab, unsigned val)
+{
+	unsigned char crc;
+
+	crc = crc_tab[val >> 16 & 0xFF];
+	crc = crc_tab[crc ^ (val >> 8 & 0xFF)];
+
+	return  crc ^ (val & 0xFF);
+}
+
+static int ad7280_check_crc(struct ad7280_state *st, unsigned val)
+{
+	unsigned char crc = ad7280_calc_crc8(st->crc_tab, val >> 10);
+
+	if (crc != ((val >> 2) & 0xFF))
+		return -EIO;
+
+	return 0;
+}
+
+/* After initiating a conversion sequence we need to wait until the
+ * conversion is done. The delay is typically in the range of 15..30 us
+ * however depending an the number of devices in the daisy chain and the
+ * number of averages taken, conversion delays and acquisition time options
+ * it may take up to 250us, in this case we better sleep instead of busy
+ * wait.
+ */
+
+static void ad7280_delay(struct ad7280_state *st)
+{
+	if (st->readback_delay_us < 50)
+		udelay(st->readback_delay_us);
+	else
+		msleep(1);
+}
+
+static int __ad7280_read32(struct spi_device *spi, unsigned *val)
+{
+	unsigned rx_buf, tx_buf = cpu_to_be32(AD7280A_READ_TXVAL);
+	int ret;
+
+	struct spi_transfer t = {
+		.tx_buf	= &tx_buf,
+		.rx_buf = &rx_buf,
+		.len = 4,
+	};
+	struct spi_message m;
+
+	spi_message_init(&m);
+	spi_message_add_tail(&t, &m);
+
+	ret = spi_sync(spi, &m);
+	if (ret)
+		return ret;
+
+	*val = be32_to_cpu(rx_buf);
+
+	return 0;
+}
+
+static int ad7280_write(struct ad7280_state *st, unsigned devaddr,
+			unsigned addr, bool all, unsigned val)
+{
+	unsigned reg = (devaddr << 27 | addr << 21 |
+			(val & 0xFF) << 13 | all << 12);
+
+	reg |= ad7280_calc_crc8(st->crc_tab, reg >> 11) << 3 | 0x2;
+	reg = cpu_to_be32(reg);
+
+	return spi_write(st->spi, &reg, 4);
+}
+
+static int ad7280_read(struct ad7280_state *st, unsigned devaddr,
+			unsigned addr)
+{
+	int ret;
+	unsigned tmp;
+
+	/* turns off the read operation on all parts */
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_CONTROL_HB, 1,
+			AD7280A_CTRL_HB_CONV_INPUT_ALL |
+			AD7280A_CTRL_HB_CONV_RES_READ_NO |
+			st->ctrl_hb);
+	if (ret)
+		return ret;
+
+	/* turns on the read operation on the addressed part */
+	ret = ad7280_write(st, devaddr, AD7280A_CONTROL_HB, 0,
+			AD7280A_CTRL_HB_CONV_INPUT_ALL |
+			AD7280A_CTRL_HB_CONV_RES_READ_ALL |
+			st->ctrl_hb);
+	if (ret)
+		return ret;
+
+	/* Set register address on the part to be read from */
+	ret = ad7280_write(st, devaddr, AD7280A_READ, 0, addr << 2);
+	if (ret)
+		return ret;
+
+	__ad7280_read32(st->spi, &tmp);
+
+	if (ad7280_check_crc(st, tmp))
+		return -EIO;
+
+	if (((tmp >> 27) != devaddr) || (((tmp >> 21) & 0x3F) != addr))
+		return -EFAULT;
+
+	return (tmp >> 13) & 0xFF;
+}
+
+static int ad7280_read_channel(struct ad7280_state *st, unsigned devaddr,
+			       unsigned addr)
+{
+	int ret;
+	unsigned tmp;
+
+	ret = ad7280_write(st, devaddr, AD7280A_READ, 0, addr << 2);
+	if (ret)
+		return ret;
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_CONTROL_HB, 1,
+			AD7280A_CTRL_HB_CONV_INPUT_ALL |
+			AD7280A_CTRL_HB_CONV_RES_READ_NO |
+			st->ctrl_hb);
+	if (ret)
+		return ret;
+
+	ret = ad7280_write(st, devaddr, AD7280A_CONTROL_HB, 0,
+			AD7280A_CTRL_HB_CONV_INPUT_ALL |
+			AD7280A_CTRL_HB_CONV_RES_READ_ALL |
+			AD7280A_CTRL_HB_CONV_START_CS |
+			st->ctrl_hb);
+	if (ret)
+		return ret;
+
+	ad7280_delay(st);
+
+	__ad7280_read32(st->spi, &tmp);
+
+	if (ad7280_check_crc(st, tmp))
+		return -EIO;
+
+	if (((tmp >> 27) != devaddr) || (((tmp >> 23) & 0xF) != addr))
+		return -EFAULT;
+
+	return (tmp >> 11) & 0xFFF;
+}
+
+static int ad7280_read_all_channels(struct ad7280_state *st, unsigned cnt,
+			     unsigned *array)
+{
+	int i, ret;
+	unsigned tmp, sum = 0;
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_READ, 1,
+			   AD7280A_CELL_VOLTAGE_1 << 2);
+	if (ret)
+		return ret;
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_CONTROL_HB, 1,
+			AD7280A_CTRL_HB_CONV_INPUT_ALL |
+			AD7280A_CTRL_HB_CONV_RES_READ_ALL |
+			AD7280A_CTRL_HB_CONV_START_CS |
+			st->ctrl_hb);
+	if (ret)
+		return ret;
+
+	ad7280_delay(st);
+
+	for (i = 0; i < cnt; i++) {
+		__ad7280_read32(st->spi, &tmp);
+
+		if (ad7280_check_crc(st, tmp))
+			return -EIO;
+
+		if (array)
+			array[i] = tmp;
+		/* only sum cell voltages */
+		if (((tmp >> 23) & 0xF) <= AD7280A_CELL_VOLTAGE_6)
+			sum += ((tmp >> 11) & 0xFFF);
+	}
+
+	return sum;
+}
+
+static int ad7280_chain_setup(struct ad7280_state *st)
+{
+	unsigned val, n;
+	int ret;
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_CONTROL_LB, 1,
+			AD7280A_CTRL_LB_DAISY_CHAIN_RB_EN |
+			AD7280A_CTRL_LB_LOCK_DEV_ADDR |
+			AD7280A_CTRL_LB_MUST_SET |
+			AD7280A_CTRL_LB_SWRST |
+			st->ctrl_lb);
+	if (ret)
+		return ret;
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_CONTROL_LB, 1,
+			AD7280A_CTRL_LB_DAISY_CHAIN_RB_EN |
+			AD7280A_CTRL_LB_LOCK_DEV_ADDR |
+			AD7280A_CTRL_LB_MUST_SET |
+			st->ctrl_lb);
+	if (ret)
+		return ret;
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_READ, 1,
+			AD7280A_CONTROL_LB << 2);
+	if (ret)
+		return ret;
+
+	for (n = 0; n <= AD7280A_MAX_CHAIN; n++) {
+		__ad7280_read32(st->spi, &val);
+		if (val == 0)
+			return n - 1;
+
+		if (ad7280_check_crc(st, val))
+			return -EIO;
+
+		if (n != AD7280A_DEVADDR(val >> 27))
+			return -EIO;
+	}
+
+	return -EFAULT;
+}
+
+static ssize_t ad7280_show_balance_sw(struct device *dev,
+					struct device_attribute *attr,
+					char *buf)
+{
+	struct iio_dev *dev_info = dev_get_drvdata(dev);
+	struct ad7280_state *st = iio_priv(dev_info);
+	struct iio_dev_attr *this_attr = to_iio_dev_attr(attr);
+
+	return sprintf(buf, "%d\n",
+		       !!(st->cb_mask[this_attr->address >> 8] &
+		       (1 << ((this_attr->address & 0xFF) + 2))));
+}
+
+static ssize_t ad7280_store_balance_sw(struct device *dev,
+					 struct device_attribute *attr,
+					 const char *buf,
+					 size_t len)
+{
+	struct iio_dev *dev_info = dev_get_drvdata(dev);
+	struct ad7280_state *st = iio_priv(dev_info);
+	struct iio_dev_attr *this_attr = to_iio_dev_attr(attr);
+	bool readin;
+	int ret;
+	unsigned devaddr, ch;
+
+	ret = strtobool(buf, &readin);
+	if (ret)
+		return ret;
+
+	devaddr = this_attr->address >> 8;
+	ch = this_attr->address & 0xFF;
+
+	mutex_lock(&dev_info->mlock);
+	if (readin)
+		st->cb_mask[devaddr] |= 1 << (ch + 2);
+	else
+		st->cb_mask[devaddr] &= ~(1 << (ch + 2));
+
+	ret = ad7280_write(st, devaddr, AD7280A_CELL_BALANCE,
+			   0, st->cb_mask[devaddr]);
+	mutex_unlock(&dev_info->mlock);
+
+	return ret ? ret : len;
+}
+
+static ssize_t ad7280_show_balance_timer(struct device *dev,
+					struct device_attribute *attr,
+					char *buf)
+{
+	struct iio_dev *dev_info = dev_get_drvdata(dev);
+	struct ad7280_state *st = iio_priv(dev_info);
+	struct iio_dev_attr *this_attr = to_iio_dev_attr(attr);
+	int ret;
+	unsigned msecs;
+
+	mutex_lock(&dev_info->mlock);
+	ret = ad7280_read(st, this_attr->address >> 8,
+			this_attr->address & 0xFF);
+	mutex_unlock(&dev_info->mlock);
+
+	if (ret < 0)
+		return ret;
+
+	msecs = (ret >> 3) * 71500;
+
+	return sprintf(buf, "%d\n", msecs);
+}
+
+static ssize_t ad7280_store_balance_timer(struct device *dev,
+					 struct device_attribute *attr,
+					 const char *buf,
+					 size_t len)
+{
+	struct iio_dev *dev_info = dev_get_drvdata(dev);
+	struct ad7280_state *st = iio_priv(dev_info);
+	struct iio_dev_attr *this_attr = to_iio_dev_attr(attr);
+	long val;
+	int ret;
+
+	ret = strict_strtoul(buf, 10, &val);
+	if (ret)
+		return ret;
+
+	val /= 71500;
+
+	if (val > 31)
+		return -EINVAL;
+
+	mutex_lock(&dev_info->mlock);
+	ret = ad7280_write(st, this_attr->address >> 8,
+			   this_attr->address & 0xFF,
+			   0, (val & 0x1F) << 3);
+	mutex_unlock(&dev_info->mlock);
+
+	return ret ? ret : len;
+}
+
+static struct attribute *ad7280_attributes[AD7280A_MAX_CHAIN *
+					   AD7280A_CELLS_PER_DEV * 2 + 1];
+
+static struct attribute_group ad7280_attrs_group = {
+	.attrs = ad7280_attributes,
+};
+
+static int ad7280_channel_init(struct ad7280_state *st)
+{
+	int dev, ch, cnt;
+
+	st->channels = kzalloc(sizeof(*st->channels) *
+				((st->slave_num + 1) * 12 + 2), GFP_KERNEL);
+	if (st->channels == NULL)
+		return -ENOMEM;
+
+	for (dev = 0, cnt = 0; dev <= st->slave_num; dev++)
+		for (ch = AD7280A_CELL_VOLTAGE_1; ch <= AD7280A_AUX_ADC_6; ch++,
+			cnt++) {
+			if (ch < AD7280A_AUX_ADC_1) {
+				st->channels[cnt].type = IIO_IN_DIFF;
+				st->channels[cnt].channel = (dev * 6) + ch;
+				st->channels[cnt].channel2 =
+					st->channels[cnt].channel + 1;
+			} else {
+				st->channels[cnt].type = IIO_TEMP;
+				st->channels[cnt].channel = (dev * 6) + ch - 6;
+			}
+			st->channels[cnt].indexed = 1;
+			st->channels[cnt].info_mask =
+				(1 << IIO_CHAN_INFO_SCALE_SHARED);
+			st->channels[cnt].address =
+				AD7280A_DEVADDR(dev) << 8 | ch;
+			st->channels[cnt].scan_index = cnt;
+			st->channels[cnt].scan_type.sign = 'u';
+			st->channels[cnt].scan_type.realbits = 12;
+			st->channels[cnt].scan_type.storagebits = 32;
+			st->channels[cnt].scan_type.shift = 0;
+		}
+
+	st->channels[cnt].type = IIO_IN_DIFF;
+	st->channels[cnt].channel = 0;
+	st->channels[cnt].channel2 = dev * 6;
+	st->channels[cnt].address = AD7280A_ALL_CELLS;
+	st->channels[cnt].indexed = 1;
+	st->channels[cnt].info_mask = (1 << IIO_CHAN_INFO_SCALE_SHARED);
+	st->channels[cnt].scan_index = cnt;
+	st->channels[cnt].scan_type.sign = 'u';
+	st->channels[cnt].scan_type.realbits = 32;
+	st->channels[cnt].scan_type.storagebits = 32;
+	st->channels[cnt].scan_type.shift = 0;
+	cnt++;
+	st->channels[cnt].type = IIO_TIMESTAMP;
+	st->channels[cnt].channel = -1;
+	st->channels[cnt].scan_index = cnt;
+	st->channels[cnt].scan_type.sign = 's';
+	st->channels[cnt].scan_type.realbits = 64;
+	st->channels[cnt].scan_type.storagebits = 64;
+	st->channels[cnt].scan_type.shift = 0;
+
+	return cnt + 1;
+}
+
+static int ad7280_attr_init(struct ad7280_state *st)
+{
+	int dev, ch, cnt;
+
+	st->iio_attr = kzalloc(sizeof(*st->iio_attr) * (st->slave_num + 1) *
+				AD7280A_CELLS_PER_DEV * 2, GFP_KERNEL);
+	if (st->iio_attr == NULL)
+		return -ENOMEM;
+
+	for (dev = 0, cnt = 0; dev <= st->slave_num; dev++)
+		for (ch = AD7280A_CELL_VOLTAGE_1; ch <= AD7280A_CELL_VOLTAGE_6;
+			ch++, cnt++) {
+			st->iio_attr[cnt].address =
+				AD7280A_DEVADDR(dev) << 8 | ch;
+			st->iio_attr[cnt].dev_attr.attr.mode =
+				S_IWUSR | S_IRUGO;
+			st->iio_attr[cnt].dev_attr.show =
+				ad7280_show_balance_sw;
+			st->iio_attr[cnt].dev_attr.store =
+				ad7280_store_balance_sw;
+			st->iio_attr[cnt].dev_attr.attr.name =
+				kasprintf(GFP_KERNEL,
+					"in%d-in%d_balance_switch_en",
+					(dev * AD7280A_CELLS_PER_DEV) + ch,
+					(dev * AD7280A_CELLS_PER_DEV) + ch + 1);
+			ad7280_attributes[cnt] =
+				&st->iio_attr[cnt].dev_attr.attr;
+			cnt++;
+			st->iio_attr[cnt].address =
+				AD7280A_DEVADDR(dev) << 8 |
+				(AD7280A_CB1_TIMER + ch);
+			st->iio_attr[cnt].dev_attr.attr.mode =
+				S_IWUSR | S_IRUGO;
+			st->iio_attr[cnt].dev_attr.show =
+				ad7280_show_balance_timer;
+			st->iio_attr[cnt].dev_attr.store =
+				ad7280_store_balance_timer;
+			st->iio_attr[cnt].dev_attr.attr.name =
+				kasprintf(GFP_KERNEL, "in%d-in%d_balance_timer",
+					(dev * AD7280A_CELLS_PER_DEV) + ch,
+					(dev * AD7280A_CELLS_PER_DEV) + ch + 1);
+			ad7280_attributes[cnt] =
+				&st->iio_attr[cnt].dev_attr.attr;
+		}
+
+	ad7280_attributes[cnt] = NULL;
+
+	return 0;
+}
+
+static ssize_t ad7280_read_channel_config(struct device *dev,
+					struct device_attribute *attr,
+					char *buf)
+{
+	struct iio_dev *dev_info = dev_get_drvdata(dev);
+	struct ad7280_state *st = iio_priv(dev_info);
+	struct iio_dev_attr *this_attr = to_iio_dev_attr(attr);
+	unsigned val;
+
+	switch (this_attr->address) {
+	case AD7280A_CELL_OVERVOLTAGE:
+		val = 1000 + (st->cell_threshhigh * 1568) / 100;
+		break;
+	case AD7280A_CELL_UNDERVOLTAGE:
+		val = 1000 + (st->cell_threshlow * 1568) / 100;
+		break;
+	case AD7280A_AUX_ADC_OVERVOLTAGE:
+		val = (st->aux_threshhigh * 196) / 10;
+		break;
+	case AD7280A_AUX_ADC_UNDERVOLTAGE:
+		val = (st->aux_threshlow * 196) / 10;
+		break;
+	default:
+		return -EINVAL;
+	}
+
+	return sprintf(buf, "%d\n", val);
+}
+
+static ssize_t ad7280_write_channel_config(struct device *dev,
+					 struct device_attribute *attr,
+					 const char *buf,
+					 size_t len)
+{
+	struct iio_dev *dev_info = dev_get_drvdata(dev);
+	struct ad7280_state *st = iio_priv(dev_info);
+	struct iio_dev_attr *this_attr = to_iio_dev_attr(attr);
+
+	long val;
+	int ret;
+
+	ret = strict_strtol(buf, 10, &val);
+	if (ret)
+		return ret;
+
+	switch (this_attr->address) {
+	case AD7280A_CELL_OVERVOLTAGE:
+	case AD7280A_CELL_UNDERVOLTAGE:
+		val = ((val - 1000) * 100) / 1568; /* LSB 15.68mV */
+		break;
+	case AD7280A_AUX_ADC_OVERVOLTAGE:
+	case AD7280A_AUX_ADC_UNDERVOLTAGE:
+		val = (val * 10) / 196; /* LSB 19.6mV */
+		break;
+	default:
+		return -EFAULT;
+	}
+
+	val = clamp(val, 0L, 0xFFL);
+
+	mutex_lock(&dev_info->mlock);
+	switch (this_attr->address) {
+	case AD7280A_CELL_OVERVOLTAGE:
+		st->cell_threshhigh = val;
+		break;
+	case AD7280A_CELL_UNDERVOLTAGE:
+		st->cell_threshlow = val;
+		break;
+	case AD7280A_AUX_ADC_OVERVOLTAGE:
+		st->aux_threshhigh = val;
+		break;
+	case AD7280A_AUX_ADC_UNDERVOLTAGE:
+		st->aux_threshlow = val;
+		break;
+	}
+
+	ret = ad7280_write(st, AD7280A_DEVADDR_MASTER,
+			   this_attr->address, 1, val);
+
+	mutex_unlock(&dev_info->mlock);
+
+	return ret ? ret : len;
+}
+
+static irqreturn_t ad7280_event_handler(int irq, void *private)
+{
+	struct iio_dev *dev_info = private;
+	struct ad7280_state *st = iio_priv(dev_info);
+	unsigned *channels;
+	int i, ret;
+
+	channels = kzalloc(sizeof(*channels) * st->scan_cnt, GFP_KERNEL);
+	if (channels == NULL)
+		return IRQ_HANDLED;
+
+	ret = ad7280_read_all_channels(st, st->scan_cnt, channels);
+	if (ret < 0)
+		return IRQ_HANDLED;
+
+	for (i = 0; i < st->scan_cnt; i++) {
+		if (((channels[i] >> 23) & 0xF) <= AD7280A_CELL_VOLTAGE_6) {
+			if (((channels[i] >> 11) & 0xFFF) >=
+				st->cell_threshhigh)
+				iio_push_event(dev_info, 0,
+					IIO_UNMOD_EVENT_CODE(IIO_IN_DIFF,
+					0,
+					IIO_EV_TYPE_THRESH,
+					IIO_EV_DIR_RISING),
+					iio_get_time_ns());
+			else if (((channels[i] >> 11) & 0xFFF) <=
+				st->cell_threshlow)
+				iio_push_event(dev_info, 0,
+					IIO_UNMOD_EVENT_CODE(IIO_IN_DIFF,
+					0,
+					IIO_EV_TYPE_THRESH,
+					IIO_EV_DIR_FALLING),
+					iio_get_time_ns());
+		} else {
+			if (((channels[i] >> 11) & 0xFFF) >= st->aux_threshhigh)
+				iio_push_event(dev_info, 0,
+					IIO_UNMOD_EVENT_CODE(IIO_TEMP,
+					0,
+					IIO_EV_TYPE_THRESH,
+					IIO_EV_DIR_RISING),
+					iio_get_time_ns());
+			else if (((channels[i] >> 11) & 0xFFF) <=
+				st->aux_threshlow)
+				iio_push_event(dev_info, 0,
+					IIO_UNMOD_EVENT_CODE(IIO_TEMP,
+					0,
+					IIO_EV_TYPE_THRESH,
+					IIO_EV_DIR_FALLING),
+					iio_get_time_ns());
+		}
+	}
+
+	kfree(channels);
+
+	return IRQ_HANDLED;
+}
+
+static IIO_DEVICE_ATTR_NAMED(in_thresh_low_value,
+		in-in_thresh_low_value,
+		S_IRUGO | S_IWUSR,
+		ad7280_read_channel_config,
+		ad7280_write_channel_config,
+		AD7280A_CELL_UNDERVOLTAGE);
+
+static IIO_DEVICE_ATTR_NAMED(in_thresh_high_value,
+		in-in_thresh_high_value,
+		S_IRUGO | S_IWUSR,
+		ad7280_read_channel_config,
+		ad7280_write_channel_config,
+		AD7280A_CELL_OVERVOLTAGE);
+
+static IIO_DEVICE_ATTR(temp_thresh_low_value,
+		S_IRUGO | S_IWUSR,
+		ad7280_read_channel_config,
+		ad7280_write_channel_config,
+		AD7280A_AUX_ADC_UNDERVOLTAGE);
+
+static IIO_DEVICE_ATTR(temp_thresh_high_value,
+		S_IRUGO | S_IWUSR,
+		ad7280_read_channel_config,
+		ad7280_write_channel_config,
+		AD7280A_AUX_ADC_OVERVOLTAGE);
+
+
+static struct attribute *ad7280_event_attributes[] = {
+	&iio_dev_attr_in_thresh_low_value.dev_attr.attr,
+	&iio_dev_attr_in_thresh_high_value.dev_attr.attr,
+	&iio_dev_attr_temp_thresh_low_value.dev_attr.attr,
+	&iio_dev_attr_temp_thresh_high_value.dev_attr.attr,
+	NULL,
+};
+
+static struct attribute_group ad7280_event_attrs_group = {
+	.attrs = ad7280_event_attributes,
+};
+
+static int ad7280_read_raw(struct iio_dev *dev_info,
+			   struct iio_chan_spec const *chan,
+			   int *val,
+			   int *val2,
+			   long m)
+{
+	struct ad7280_state *st = iio_priv(dev_info);
+	unsigned int scale_uv;
+	int ret;
+
+	switch (m) {
+	case 0:
+		mutex_lock(&dev_info->mlock);
+		if (chan->address == AD7280A_ALL_CELLS)
+			ret = ad7280_read_all_channels(st, st->scan_cnt, NULL);
+		else
+			ret = ad7280_read_channel(st, chan->address >> 8,
+						  chan->address & 0xFF);
+		mutex_unlock(&dev_info->mlock);
+
+		if (ret < 0)
+			return ret;
+
+		*val = ret;
+
+		return IIO_VAL_INT;
+	case (1 << IIO_CHAN_INFO_SCALE_SHARED):
+		if ((chan->address & 0xFF) <= AD7280A_CELL_VOLTAGE_6)
+			scale_uv = (4000 * 1000) >> AD7280A_BITS;
+		else
+			scale_uv = (5000 * 1000) >> AD7280A_BITS;
+
+		*val =  scale_uv / 1000;
+		*val2 = (scale_uv % 1000) * 1000;
+		return IIO_VAL_INT_PLUS_MICRO;
+	}
+	return -EINVAL;
+}
+
+static const struct iio_info ad7280_info = {
+	.read_raw = &ad7280_read_raw,
+	.num_interrupt_lines = 1,
+	.event_attrs = &ad7280_event_attrs_group,
+	.attrs = &ad7280_attrs_group,
+	.driver_module = THIS_MODULE,
+};
+
+static const struct ad7280_platform_data ad7793_default_pdata = {
+	.acquisition_time = AD7280A_ACQ_TIME_400ns,
+	.conversion_averaging = AD7280A_CONV_AVG_DIS,
+	.thermistor_term_en = true,
+};
+
+static int __devinit ad7280_probe(struct spi_device *spi)
+{
+	const struct ad7280_platform_data *pdata = spi->dev.platform_data;
+	struct ad7280_state *st;
+	int ret, regdone = 0;
+	const unsigned short tACQ_ns[4] = {465, 1010, 1460, 1890};
+	const unsigned short nAVG[4] = {1, 2, 4, 8};
+	struct iio_dev *indio_dev = iio_allocate_device(sizeof(*st));
+
+	if (indio_dev == NULL)
+		return -ENOMEM;
+
+	st = iio_priv(indio_dev);
+	spi_set_drvdata(spi, indio_dev);
+	st->spi = spi;
+
+	if (!pdata)
+		pdata = &ad7793_default_pdata;
+
+	ad7280_crc8_build_table(st->crc_tab);
+
+	st->spi->max_speed_hz = AD7280A_MAX_SPI_CLK_Hz;
+	st->spi->mode = SPI_MODE_1;
+	spi_setup(st->spi);
+
+	st->ctrl_lb = AD7280A_CTRL_LB_ACQ_TIME(pdata->acquisition_time & 0x3);
+	st->ctrl_hb = AD7280A_CTRL_HB_CONV_AVG(pdata->conversion_averaging
+			& 0x3) | (pdata->thermistor_term_en ?
+			AD7280A_CTRL_LB_THERMISTOR_EN : 0);
+
+	ret = ad7280_chain_setup(st);
+	if (ret < 0)
+		goto error_free_device;
+
+	st->slave_num = ret;
+	st->scan_cnt = (st->slave_num + 1) * AD7280A_NUM_CH;
+	st->cell_threshhigh = 0xFF;
+	st->aux_threshhigh = 0xFF;
+
+	/*
+	 * Total Conversion Time = ((tACQ + tCONV) *
+	 *			   (Number of Conversions per Part)) â??
+	 *			   tACQ + ((N - 1) * tDELAY)
+	 *
+	 * Readback Delay = Total Conversion Time + tWAIT
+	 */
+
+	st->readback_delay_us =
+		((tACQ_ns[pdata->acquisition_time & 0x3] + 695) *
+		(AD7280A_NUM_CH * nAVG[pdata->conversion_averaging & 0x3]))
+		- tACQ_ns[pdata->acquisition_time & 0x3] +
+		st->slave_num * 250;
+
+	/* Convert to usecs */
+	st->readback_delay_us = DIV_ROUND_UP(st->readback_delay_us, 1000);
+	st->readback_delay_us += 5; /* Add tWAIT */
+
+	indio_dev->name = spi_get_device_id(spi)->name;
+	indio_dev->dev.parent = &spi->dev;
+	indio_dev->modes = INDIO_DIRECT_MODE;
+
+	ret = ad7280_channel_init(st);
+	if (ret < 0)
+		goto error_free_device;
+
+	indio_dev->num_channels = ret;
+	indio_dev->channels = st->channels;
+	indio_dev->info = &ad7280_info;
+
+	ret = ad7280_attr_init(st);
+	if (ret < 0)
+		goto error_free_channels;
+
+	ret = iio_device_register(indio_dev);
+	if (ret)
+		goto error_free_attr;
+	regdone = 1;
+
+	if (spi->irq > 0) {
+		ret = ad7280_write(st, AD7280A_DEVADDR_MASTER,
+				   AD7280A_ALERT, 1,
+				   AD7280A_ALERT_RELAY_SIG_CHAIN_DOWN);
+		if (ret)
+			goto error_free_attr;
+
+		ret = ad7280_write(st, AD7280A_DEVADDR(st->slave_num),
+				   AD7280A_ALERT, 0,
+				   AD7280A_ALERT_GEN_STATIC_HIGH |
+				   (pdata->chain_last_alert_ignore & 0xF));
+		if (ret)
+			goto error_free_attr;
+
+		ret = request_threaded_irq(spi->irq,
+					   NULL,
+					   ad7280_event_handler,
+					   IRQF_TRIGGER_FALLING |
+					   IRQF_ONESHOT,
+					   indio_dev->name,
+					   indio_dev);
+		if (ret)
+			goto error_free_attr;
+	}
+
+	return 0;
+
+error_free_attr:
+	kfree(st->iio_attr);
+
+error_free_channels:
+	kfree(st->channels);
+
+error_free_device:
+	if (regdone)
+		iio_device_unregister(indio_dev);
+	else
+		iio_free_device(indio_dev);
+
+	return ret;
+}
+
+static int __devexit ad7280_remove(struct spi_device *spi)
+{
+	struct iio_dev *indio_dev = spi_get_drvdata(spi);
+	struct ad7280_state *st = iio_priv(indio_dev);
+
+	if (spi->irq > 0)
+		free_irq(spi->irq, indio_dev);
+
+	ad7280_write(st, AD7280A_DEVADDR_MASTER, AD7280A_CONTROL_HB, 1,
+			AD7280A_CTRL_HB_PWRDN_SW | st->ctrl_hb);
+
+	kfree(st->channels);
+	kfree(st->iio_attr);
+	iio_device_unregister(indio_dev);
+
+	return 0;
+}
+
+static const struct spi_device_id ad7280_id[] = {
+	{"ad7280a", 0},
+	{}
+};
+
+static struct spi_driver ad7280_driver = {
+	.driver = {
+		.name	= "ad7280",
+		.bus	= &spi_bus_type,
+		.owner	= THIS_MODULE,
+	},
+	.probe		= ad7280_probe,
+	.remove		= __devexit_p(ad7280_remove),
+	.id_table	= ad7280_id,
+};
+
+static int __init ad7280_init(void)
+{
+	return spi_register_driver(&ad7280_driver);
+}
+module_init(ad7280_init);
+
+static void __exit ad7280_exit(void)
+{
+	spi_unregister_driver(&ad7280_driver);
+}
+module_exit(ad7280_exit);
+
+MODULE_AUTHOR("Michael Hennerich <hennerich@xxxxxxxxxxxxxxxxxxxx>");
+MODULE_DESCRIPTION("Analog Devices AD7280A");
+MODULE_LICENSE("GPL v2");
diff --git a/drivers/staging/iio/adc/ad7280a.h b/drivers/staging/iio/adc/ad7280a.h
new file mode 100644
index 0000000..20400b0
--- /dev/null
+++ b/drivers/staging/iio/adc/ad7280a.h
@@ -0,0 +1,38 @@
+/*
+ * AD7280A Lithium Ion Battery Monitoring System
+ *
+ * Copyright 2011 Analog Devices Inc.
+ *
+ * Licensed under the GPL-2.
+ */
+
+#ifndef IIO_ADC_AD7280_H_
+#define IIO_ADC_AD7280_H_
+
+/*
+ * TODO: struct ad7280_platform_data needs to go into include/linux/iio
+ */
+
+#define AD7280A_ACQ_TIME_400ns			0
+#define AD7280A_ACQ_TIME_800ns			1
+#define AD7280A_ACQ_TIME_1200ns			2
+#define AD7280A_ACQ_TIME_1600ns			3
+
+#define AD7280A_CONV_AVG_DIS			0
+#define AD7280A_CONV_AVG_2			1
+#define AD7280A_CONV_AVG_4			2
+#define AD7280A_CONV_AVG_8			3
+
+#define AD7280A_ALERT_REMOVE_VIN5		(1 << 2)
+#define AD7280A_ALERT_REMOVE_VIN4_VIN5		(2 << 2)
+#define AD7280A_ALERT_REMOVE_AUX5		(1 << 0)
+#define AD7280A_ALERT_REMOVE_AUX4_AUX5		(2 << 0)
+
+struct ad7280_platform_data {
+	unsigned acquisition_time;
+	unsigned conversion_averaging;
+	unsigned chain_last_alert_ignore;
+	bool thermistor_term_en;
+};
+
+#endif /* IIO_ADC_AD7280_H_ */
-- 
1.7.0.4


--
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