1
0
Fork 0

Staging: IIO: VTI sca3000 series accelerometer driver (spi)

Example of how a device with a hardware ring buffer is
handled within IIO.

Changes since V2:
* Moved to new registration functions giving much cleaner
  interface.

Signed-off-by: Jonathan Cameron <jic23@cam.ac.uk>
Signed-off-by: Greg Kroah-Hartman <gregkh@suse.de>
wifi-calibration
Jonathan Cameron 2009-08-18 18:06:25 +01:00 committed by Greg Kroah-Hartman
parent 7026ea4b52
commit 574fb258d6
6 changed files with 2171 additions and 0 deletions

View File

@ -17,3 +17,11 @@ config LIS3L02DQ
Say yes here to build SPI support for the ST microelectronics Say yes here to build SPI support for the ST microelectronics
accelerometer. The driver supplies direct access via sysfs files accelerometer. The driver supplies direct access via sysfs files
and an event interface via a character device. and an event interface via a character device.
config SCA3000
depends on IIO_RING_BUFFER
depends on SPI
tristate "VTI SCA3000 series accelerometers"
help
Say yes here to build support for the VTI SCA3000 series of SPI
accelerometers. These devices use a hardware ring buffer.

View File

@ -5,3 +5,6 @@ obj-$(CONFIG_KXSD9) += kxsd9.o
lis3l02dq-y := lis3l02dq_core.o lis3l02dq-y := lis3l02dq_core.o
obj-$(CONFIG_LIS3L02DQ) += lis3l02dq.o obj-$(CONFIG_LIS3L02DQ) += lis3l02dq.o
sca3000-y := sca3000_core.o sca3000_ring.o
obj-$(CONFIG_SCA3000) += sca3000.o

View File

@ -0,0 +1,298 @@
/*
* sca3000.c -- support VTI sca3000 series accelerometers
* via SPI
*
* Copyright (c) 2007 Jonathan Cameron <jic23@cam.ac.uk>
*
* Partly based upon tle62x0.c
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 as
* published by the Free Software Foundation.
*
* Initial mode is direct measurement.
*
* Untested things
*
* Temperature reading (the e05 I'm testing with doesn't have a sensor)
*
* Free fall detection mode - supported but untested as I'm not droping my
* dubious wire rig far enough to test it.
*
* Unsupported as yet
*
* Time stamping of data from ring. Various ideas on how to do this but none
* are remotely simple. Suggestions welcome.
*
* Individual enabling disabling of channels going into ring buffer
*
* Overflow handling (this is signaled for all but 8 bit ring buffer mode.)
*
* Motion detector using AND combinations of signals.
*
* Note: Be very careful about not touching an register bytes marked
* as reserved on the data sheet. They really mean it as changing convents of
* some will cause the device to lock up.
*
* Known issues - on rare occasions the interrupts lock up. Not sure why as yet.
* Can probably alleviate this by reading the interrupt register on start, but
* that is really just brushing the problem under the carpet.
*/
#define SCA3000_WRITE_REG(a) (((a) << 2) | 0x02)
#define SCA3000_READ_REG(a) ((a) << 2)
#define SCA3000_REG_ADDR_REVID 0x00
#define SCA3000_REVID_MAJOR_MASK 0xf0
#define SCA3000_REVID_MINOR_MASK 0x0f
#define SCA3000_REG_ADDR_STATUS 0x02
#define SCA3000_LOCKED 0x20
#define SCA3000_EEPROM_CS_ERROR 0x02
#define SCA3000_SPI_FRAME_ERROR 0x01
/* All reads done using register decrement so no need to directly access LSBs */
#define SCA3000_REG_ADDR_X_MSB 0x05
#define SCA3000_REG_ADDR_Y_MSB 0x07
#define SCA3000_REG_ADDR_Z_MSB 0x09
#define SCA3000_REG_ADDR_RING_OUT 0x0f
/* Temp read untested - the e05 doesn't have the sensor */
#define SCA3000_REG_ADDR_TEMP_MSB 0x13
#define SCA3000_REG_ADDR_MODE 0x14
#define SCA3000_MODE_PROT_MASK 0x28
#define SCA3000_RING_BUF_ENABLE 0x80
#define SCA3000_RING_BUF_8BIT 0x40
/* Free fall detection triggers an interrupt if the acceleration
* is below a threshold for equivalent of 25cm drop
*/
#define SCA3000_FREE_FALL_DETECT 0x10
#define SCA3000_MEAS_MODE_NORMAL 0x00
#define SCA3000_MEAS_MODE_OP_1 0x01
#define SCA3000_MEAS_MODE_OP_2 0x02
/* In motion detection mode the accelerations are band pass filtered
* (aprox 1 - 25Hz) and then a programmable theshold used to trigger
* and interrupt.
*/
#define SCA3000_MEAS_MODE_MOT_DET 0x03
#define SCA3000_REG_ADDR_BUF_COUNT 0x15
#define SCA3000_REG_ADDR_INT_STATUS 0x16
#define SCA3000_INT_STATUS_THREE_QUARTERS 0x80
#define SCA3000_INT_STATUS_HALF 0x40
#define SCA3000_INT_STATUS_FREE_FALL 0x08
#define SCA3000_INT_STATUS_Y_TRIGGER 0x04
#define SCA3000_INT_STATUS_X_TRIGGER 0x02
#define SCA3000_INT_STATUS_Z_TRIGGER 0x01
/* Used to allow accesss to multiplexed registers */
#define SCA3000_REG_ADDR_CTRL_SEL 0x18
/* Only available for SCA3000-D03 and SCA3000-D01 */
#define SCA3000_REG_CTRL_SEL_I2C_DISABLE 0x01
#define SCA3000_REG_CTRL_SEL_MD_CTRL 0x02
#define SCA3000_REG_CTRL_SEL_MD_Y_TH 0x03
#define SCA3000_REG_CTRL_SEL_MD_X_TH 0x04
#define SCA3000_REG_CTRL_SEL_MD_Z_TH 0x05
/* BE VERY CAREFUL WITH THIS, IF 3 BITS ARE NOT SET the device
will not function */
#define SCA3000_REG_CTRL_SEL_OUT_CTRL 0x0B
#define SCA3000_OUT_CTRL_PROT_MASK 0xE0
#define SCA3000_OUT_CTRL_BUF_X_EN 0x10
#define SCA3000_OUT_CTRL_BUF_Y_EN 0x08
#define SCA3000_OUT_CTRL_BUF_Z_EN 0x04
#define SCA3000_OUT_CTRL_BUF_DIV_4 0x02
#define SCA3000_OUT_CTRL_BUF_DIV_2 0x01
/* Control which motion detector interrupts are on.
* For now only OR combinations are supported.x
*/
#define SCA3000_MD_CTRL_PROT_MASK 0xC0
#define SCA3000_MD_CTRL_OR_Y 0x01
#define SCA3000_MD_CTRL_OR_X 0x02
#define SCA3000_MD_CTRL_OR_Z 0x04
/* Currently unsupported */
#define SCA3000_MD_CTRL_AND_Y 0x08
#define SCA3000_MD_CTRL_AND_X 0x10
#define SAC3000_MD_CTRL_AND_Z 0x20
/* Some control registers of complex access methods requiring this register to
* be used to remove a lock.
*/
#define SCA3000_REG_ADDR_UNLOCK 0x1e
#define SCA3000_REG_ADDR_INT_MASK 0x21
#define SCA3000_INT_MASK_PROT_MASK 0x1C
#define SCA3000_INT_MASK_RING_THREE_QUARTER 0x80
#define SCA3000_INT_MASK_RING_HALF 0x40
#define SCA3000_INT_MASK_ALL_INTS 0x02
#define SCA3000_INT_MASK_ACTIVE_HIGH 0x01
#define SCA3000_INT_MASK_ACTIVE_LOW 0x00
/* Values of mulipexed registers (write to ctrl_data after select) */
#define SCA3000_REG_ADDR_CTRL_DATA 0x22
/* Measurment modes available on some sca3000 series chips. Code assumes others
* may become available in the future.
*
* Bypass - Bypass the low-pass filter in the signal channel so as to increase
* signal bandwidth.
*
* Narrow - Narrow low-pass filtering of the signal channel and half output
* data rate by decimation.
*
* Wide - Widen low-pass filtering of signal channel to increase bandwidth
*/
#define SCA3000_OP_MODE_BYPASS 0x01
#define SCA3000_OP_MODE_NARROW 0x02
#define SCA3000_OP_MODE_WIDE 0x04
#define SCA3000_MAX_TX 6
#define SCA3000_MAX_RX 2
/**
* struct sca3000_state - device instance state information
* @us: the associated spi device
* @info: chip variant information
* @indio_dev: device information used by the IIO core
* @interrupt_handler_ws: event interrupt handler for all events
* @last_timestamp: the timestamp of the last event
* @mo_det_use_count: reference counter for the motion detection unit
* @lock: lock used to protect elements of sca3000_state
* and the underlying device state.
* @bpse: number of bits per scan element
* @tx: dma-able transmit buffer
* @rx: dma-able receive buffer
**/
struct sca3000_state {
struct spi_device *us;
const struct sca3000_chip_info *info;
struct iio_dev *indio_dev;
struct work_struct interrupt_handler_ws;
s64 last_timestamp;
int mo_det_use_count;
struct mutex lock;
int bpse;
u8 *tx;
/* not used during a ring buffer read */
u8 *rx;
};
/**
* struct sca3000_chip_info - model dependant parameters
* @name: model identification
* @temp_output: some devices have temperature sensors.
* @measurement_mode_freq: normal mode sampling frequency
* @option_mode_1: first optional mode. Not all models have one
* @option_mode_1_freq: option mode 1 sampling frequency
* @option_mode_2: second optional mode. Not all chips have one
* @option_mode_2_freq: option mode 2 sampling frequency
*
* This structure is used to hold information about the functionality of a given
* sca3000 variant.
**/
struct sca3000_chip_info {
const char *name;
bool temp_output;
int measurement_mode_freq;
int option_mode_1;
int option_mode_1_freq;
int option_mode_2;
int option_mode_2_freq;
};
/**
* sca3000_read_data() read a series of values from the device
* @dev: device
* @reg_address_high: start address (decremented read)
* @rx: pointer where recieved data is placed. Callee
* responsible for freeing this.
* @len: number of bytes to read
*
* The main lock must be held.
**/
int sca3000_read_data(struct sca3000_state *st,
u8 reg_address_high,
u8 **rx_p,
int len);
/**
* sca3000_write_reg() write a single register
* @address: address of register on chip
* @val: value to be written to register
*
* The main lock must be held.
**/
int sca3000_write_reg(struct sca3000_state *st, u8 address, u8 val);
/* Conversion function for use with the ring buffer when in 11bit mode */
static inline int sca3000_11bit_convert(uint8_t msb, uint8_t lsb)
{
int16_t val;
val = ((lsb >> 3) & 0x1C) | (msb << 5);
val |= (val & (1 << 12)) ? 0xE000 : 0;
return val;
};
static inline int sca3000_13bit_convert(uint8_t msb, uint8_t lsb)
{
s16 val;
val = ((lsb >> 3) & 0x1F) | (msb << 5);
/* sign fill */
val |= (val & (1 << 12)) ? 0xE000 : 0;
return val;
};
#ifdef CONFIG_IIO_RING_BUFFER
/**
* sca3000_register_ring_funcs() setup the ring state change functions
**/
void sca3000_register_ring_funcs(struct iio_dev *indio_dev);
/**
* sca3000_configure_ring() - allocate and configure ring buffer
* @indio_dev: iio-core device whose ring is to be configured
*
* The hardware ring buffer needs far fewer ring buffer functions than
* a software one as a lot of things are handled automatically.
* This function also tells the iio core that our device supports a
* hardware ring buffer mode.
**/
int sca3000_configure_ring(struct iio_dev *indio_dev);
/**
* sca3000_unconfigure_ring() - deallocate the ring buffer
* @indio_dev: iio-core device whose ring we are freeing
**/
void sca3000_unconfigure_ring(struct iio_dev *indio_dev);
/**
* sca3000_ring_int_process() handles ring related event pushing and escalation
* @val: the event code
**/
void sca3000_ring_int_process(u8 val, struct iio_ring_buffer *ring);
#else
static inline void sca3000_register_ring_funcs(struct iio_dev *indio_dev) {};
static inline
int sca3000_register_ring_access_and_init(struct iio_dev *indio_dev)
{
return 0;
};
static inline void sca3000_ring_int_process(u8 val, void *ring) {};
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,331 @@
/*
* sca3000_ring.c -- support VTI sca3000 series accelerometers via SPI
*
* This program is free software; you can redistribute it and/or modify it
* under the terms of the GNU General Public License version 2 as published by
* the Free Software Foundation.
*
* Copyright (c) 2009 Jonathan Cameron <jic23@cam.ac.uk>
*
*/
#include <linux/interrupt.h>
#include <linux/gpio.h>
#include <linux/fs.h>
#include <linux/device.h>
#include <linux/kernel.h>
#include <linux/spi/spi.h>
#include <linux/sysfs.h>
#include "../iio.h"
#include "../sysfs.h"
#include "../ring_generic.h"
#include "../ring_hw.h"
#include "accel.h"
#include "sca3000.h"
/* RFC / future work
*
* The internal ring buffer doesn't actually change what it holds depending
* on which signals are enabled etc, merely whether you can read them.
* As such the scan mode selection is somewhat different than for a software
* ring buffer and changing it actually covers any data already in the buffer.
* Currently scan elements aren't configured so it doesn't matter.
*/
/**
* sca3000_rip_hw_rb() - main ring access function, pulls data from ring
* @r: the ring
* @count: number of samples to try and pull
* @data: output the actual samples pulled from the hw ring
* @dead_offset: cheating a bit here: Set to 1 so as to allow for the
* leading byte used in bus comms.
*
* Currently does not provide timestamps. As the hardware doesn't add them they
* can only be inferred aproximately from ring buffer events such as 50% full
* and knowledge of when buffer was last emptied. This is left to userspace.
**/
static int sca3000_rip_hw_rb(struct iio_ring_buffer *r,
size_t count, u8 **data, int *dead_offset)
{
struct iio_hw_ring_buffer *hw_ring = iio_to_hw_ring_buf(r);
struct iio_dev *indio_dev = hw_ring->private;
struct sca3000_state *st = indio_dev->dev_data;
u8 *rx;
int ret, num_available, num_read = 0;
int bytes_per_sample = 1;
if (st->bpse == 11)
bytes_per_sample = 2;
mutex_lock(&st->lock);
/* Check how much data is available:
* RFC: Implement an ioctl to not bother checking whether there
* is enough data in the ring? Afterall, if we are responding
* to an interrupt we have a minimum content guaranteed so it
* seems slight silly to waste time checking it is there.
*/
ret = sca3000_read_data(st,
SCA3000_REG_ADDR_BUF_COUNT,
&rx, 1);
if (ret)
goto error_ret;
else
num_available = rx[1];
/* num_available is the total number of samples available
* i.e. number of time points * number of channels.
*/
kfree(rx);
if (count > num_available * bytes_per_sample)
num_read = num_available*bytes_per_sample;
else
num_read = count - (count % (bytes_per_sample));
/* Avoid the read request byte */
*dead_offset = 1;
ret = sca3000_read_data(st,
SCA3000_REG_ADDR_RING_OUT,
data, num_read);
error_ret:
mutex_unlock(&st->lock);
return ret ? ret : num_read;
}
/* This is only valid with all 3 elements enabled */
static int sca3000_ring_get_length(struct iio_ring_buffer *r)
{
return 64;
}
/* only valid if resolution is kept at 11bits */
static int sca3000_ring_get_bpd(struct iio_ring_buffer *r)
{
return 6;
}
static void sca3000_ring_release(struct device *dev)
{
struct iio_ring_buffer *r = to_iio_ring_buffer(dev);
kfree(iio_to_hw_ring_buf(r));
}
static IIO_RING_ENABLE_ATTR;
static IIO_RING_BPS_ATTR;
static IIO_RING_LENGTH_ATTR;
/**
* sca3000_show_ring_bpse() -sysfs function to query bits per sample from ring
* @dev: ring buffer device
* @attr: this device attribute
* @buf: buffer to write to
**/
static ssize_t sca3000_show_ring_bpse(struct device *dev,
struct device_attribute *attr,
char *buf)
{
int len = 0, ret;
u8 *rx;
struct iio_ring_buffer *r = dev_get_drvdata(dev);
struct sca3000_state *st = r->indio_dev->dev_data;
mutex_lock(&st->lock);
ret = sca3000_read_data(st, SCA3000_REG_ADDR_MODE, &rx, 1);
if (ret)
goto error_ret;
len = sprintf(buf, "%d\n", (rx[1] & SCA3000_RING_BUF_8BIT) ? 8 : 11);
kfree(rx);
error_ret:
mutex_unlock(&st->lock);
return ret ? ret : len;
}
/**
* sca3000_store_ring_bpse() - bits per scan element
* @dev: ring buffer device
* @attr: attribute called from
* @buf: input from userspace
* @len: length of input
**/
static ssize_t sca3000_store_ring_bpse(struct device *dev,
struct device_attribute *attr,
const char *buf,
size_t len)
{
struct iio_ring_buffer *r = dev_get_drvdata(dev);
struct sca3000_state *st = r->indio_dev->dev_data;
int ret;
u8 *rx;
long val;
ret = strict_strtol(buf, 10, &val);
if (ret)
return ret;
mutex_lock(&st->lock);
ret = sca3000_read_data(st, SCA3000_REG_ADDR_MODE, &rx, 1);
if (!ret)
switch (val) {
case 8:
ret = sca3000_write_reg(st, SCA3000_REG_ADDR_MODE,
rx[1] | SCA3000_RING_BUF_8BIT);
st->bpse = 8;
break;
case 11:
ret = sca3000_write_reg(st, SCA3000_REG_ADDR_MODE,
rx[1] & ~SCA3000_RING_BUF_8BIT);
st->bpse = 11;
break;
default:
ret = -EINVAL;
break;
}
mutex_unlock(&st->lock);
return ret ? ret : len;
}
static IIO_CONST_ATTR(bpse_available, "8 11");
static IIO_DEV_ATTR_BPSE(S_IRUGO | S_IWUSR,
sca3000_show_ring_bpse,
sca3000_store_ring_bpse);
/*
* Ring buffer attributes
* This device is a bit unusual in that the sampling frequency and bpse
* only apply to the ring buffer. At all times full rate and accuracy
* is available via direct reading from registers.
*/
static struct attribute *iio_ring_attributes[] = {
&dev_attr_length.attr,
&dev_attr_bps.attr,
&dev_attr_ring_enable.attr,
&iio_dev_attr_bpse.dev_attr.attr,
&iio_const_attr_bpse_available.dev_attr.attr,
NULL,
};
static struct attribute_group sca3000_ring_attr = {
.attrs = iio_ring_attributes,
};
static struct attribute_group *sca3000_ring_attr_groups[] = {
&sca3000_ring_attr,
NULL
};
static struct device_type sca3000_ring_type = {
.release = sca3000_ring_release,
.groups = sca3000_ring_attr_groups,
};
static struct iio_ring_buffer *sca3000_rb_allocate(struct iio_dev *indio_dev)
{
struct iio_ring_buffer *buf;
struct iio_hw_ring_buffer *ring;
ring = kzalloc(sizeof *ring, GFP_KERNEL);
if (!ring)
return 0;
ring->private = indio_dev;
buf = &ring->buf;
iio_ring_buffer_init(buf, indio_dev);
buf->dev.type = &sca3000_ring_type;
device_initialize(&buf->dev);
buf->dev.parent = &indio_dev->dev;
dev_set_drvdata(&buf->dev, (void *)buf);
return buf;
}
static inline void sca3000_rb_free(struct iio_ring_buffer *r)
{
if (r)
iio_put_ring_buffer(r);
}
int sca3000_configure_ring(struct iio_dev *indio_dev)
{
indio_dev->ring = sca3000_rb_allocate(indio_dev);
if (indio_dev->ring == NULL)
return -ENOMEM;
indio_dev->modes |= INDIO_RING_HARDWARE_BUFFER;
indio_dev->ring->access.rip_lots = &sca3000_rip_hw_rb;
indio_dev->ring->access.get_length = &sca3000_ring_get_length;
indio_dev->ring->access.get_bpd = &sca3000_ring_get_bpd;
return 0;
}
void sca3000_unconfigure_ring(struct iio_dev *indio_dev)
{
sca3000_rb_free(indio_dev->ring);
}
static inline
int __sca3000_hw_ring_state_set(struct iio_dev *indio_dev, bool state)
{
struct sca3000_state *st = indio_dev->dev_data;
int ret;
u8 *rx;
mutex_lock(&st->lock);
ret = sca3000_read_data(st, SCA3000_REG_ADDR_MODE, &rx, 1);
if (ret)
goto error_ret;
if (state) {
printk(KERN_INFO "supposedly enabling ring buffer\n");
ret = sca3000_write_reg(st,
SCA3000_REG_ADDR_MODE,
(rx[1] | SCA3000_RING_BUF_ENABLE));
} else
ret = sca3000_write_reg(st,
SCA3000_REG_ADDR_MODE,
(rx[1] & ~SCA3000_RING_BUF_ENABLE));
kfree(rx);
error_ret:
mutex_unlock(&st->lock);
return ret;
}
/**
* sca3000_hw_ring_preenable() hw ring buffer preenable function
*
* Very simple enable function as the chip will allows normal reads
* during ring buffer operation so as long as it is indeed running
* before we notify the core, the precise ordering does not matter.
**/
static int sca3000_hw_ring_preenable(struct iio_dev *indio_dev)
{
return __sca3000_hw_ring_state_set(indio_dev, 1);
}
static int sca3000_hw_ring_postdisable(struct iio_dev *indio_dev)
{
return __sca3000_hw_ring_state_set(indio_dev, 0);
}
void sca3000_register_ring_funcs(struct iio_dev *indio_dev)
{
indio_dev->ring->preenable = &sca3000_hw_ring_preenable;
indio_dev->ring->postdisable = &sca3000_hw_ring_postdisable;
}
/**
* sca3000_ring_int_process() ring specific interrupt handling.
*
* This is only split from the main interrupt handler so as to
* reduce the amount of code if the ring buffer is not enabled.
**/
void sca3000_ring_int_process(u8 val, struct iio_ring_buffer *ring)
{
if (val & SCA3000_INT_STATUS_THREE_QUARTERS)
iio_push_or_escallate_ring_event(ring,
IIO_EVENT_CODE_RING_75_FULL,
0);
else if (val & SCA3000_INT_STATUS_HALF)
iio_push_ring_event(ring,
IIO_EVENT_CODE_RING_50_FULL, 0);
}

View File

@ -0,0 +1,22 @@
/*
* ring_hw.h - common functionality for iio hardware ring buffers
*
* This program is free software; you can redistribute it and/or modify it
* under the terms of the GNU General Public License version 2 as published by
* the Free Software Foundation.
*
* Copyright (c) 2009 Jonathan Cameron <jic23@cam.ac.uk>
*
*/
/**
* struct iio_hw_ring_buffer- hardware ring buffer
* @buf: generic ring buffer elements
* @private: device specific data
*/
struct iio_hw_ring_buffer {
struct iio_ring_buffer buf;
void *private;
};
#define iio_to_hw_ring_buf(r) container_of(r, struct iio_hw_ring_buffer, buf)