summaryrefslogtreecommitdiff
path: root/include
diff options
context:
space:
mode:
Diffstat (limited to 'include')
-rw-r--r--include/linux/hid-sensor-hub.h38
-rw-r--r--include/linux/hid-sensor-ids.h9
-rw-r--r--include/linux/iio/buffer.h13
-rw-r--r--include/linux/iio/common/st_sensors.h280
-rw-r--r--include/linux/iio/common/st_sensors_i2c.h20
-rw-r--r--include/linux/iio/common/st_sensors_spi.h20
-rw-r--r--include/linux/iio/consumer.h14
-rw-r--r--include/linux/iio/driver.h9
-rw-r--r--include/linux/iio/gyro/itg3200.h154
-rw-r--r--include/linux/iio/trigger.h5
-rw-r--r--include/linux/pci_ids.h10
-rw-r--r--include/linux/platform_data/invensense_mpu6050.h31
-rw-r--r--include/linux/platform_data/tsl2563.h8
-rw-r--r--include/linux/spi/spi.h44
14 files changed, 630 insertions, 25 deletions
diff --git a/include/linux/hid-sensor-hub.h b/include/linux/hid-sensor-hub.h
index 0aa5f4c42ae..ecefb7311dd 100644
--- a/include/linux/hid-sensor-hub.h
+++ b/include/linux/hid-sensor-hub.h
@@ -157,4 +157,42 @@ int sensor_hub_set_feature(struct hid_sensor_hub_device *hsdev, u32 report_id,
*/
int sensor_hub_get_feature(struct hid_sensor_hub_device *hsdev, u32 report_id,
u32 field_index, s32 *value);
+
+/* hid-sensor-attributes */
+
+/* Common hid sensor iio structure */
+struct hid_sensor_common {
+ struct hid_sensor_hub_device *hsdev;
+ struct platform_device *pdev;
+ unsigned usage_id;
+ bool data_ready;
+ struct hid_sensor_hub_attribute_info poll;
+ struct hid_sensor_hub_attribute_info report_state;
+ struct hid_sensor_hub_attribute_info power_state;
+ struct hid_sensor_hub_attribute_info sensitivity;
+};
+
+/*Convert from hid unit expo to regular exponent*/
+static inline int hid_sensor_convert_exponent(int unit_expo)
+{
+ if (unit_expo < 0x08)
+ return unit_expo;
+ else if (unit_expo <= 0x0f)
+ return -(0x0f-unit_expo+1);
+ else
+ return 0;
+}
+
+int hid_sensor_parse_common_attributes(struct hid_sensor_hub_device *hsdev,
+ u32 usage_id,
+ struct hid_sensor_common *st);
+int hid_sensor_write_raw_hyst_value(struct hid_sensor_common *st,
+ int val1, int val2);
+int hid_sensor_read_raw_hyst_value(struct hid_sensor_common *st,
+ int *val1, int *val2);
+int hid_sensor_write_samp_freq_value(struct hid_sensor_common *st,
+ int val1, int val2);
+int hid_sensor_read_samp_freq_value(struct hid_sensor_common *st,
+ int *val1, int *val2);
+
#endif
diff --git a/include/linux/hid-sensor-ids.h b/include/linux/hid-sensor-ids.h
index 55f277372fe..6f24446e766 100644
--- a/include/linux/hid-sensor-ids.h
+++ b/include/linux/hid-sensor-ids.h
@@ -66,6 +66,15 @@
#define HID_USAGE_SENSOR_ORIENT_MAGN_FLUX_Y_AXIS 0x200486
#define HID_USAGE_SENSOR_ORIENT_MAGN_FLUX_Z_AXIS 0x200487
+/* Time (2000a0) */
+#define HID_USAGE_SENSOR_TIME 0x2000a0
+#define HID_USAGE_SENSOR_TIME_YEAR 0x200521
+#define HID_USAGE_SENSOR_TIME_MONTH 0x200522
+#define HID_USAGE_SENSOR_TIME_DAY 0x200523
+#define HID_USAGE_SENSOR_TIME_HOUR 0x200525
+#define HID_USAGE_SENSOR_TIME_MINUTE 0x200526
+#define HID_USAGE_SENSOR_TIME_SECOND 0x200527
+
/* Units */
#define HID_USAGE_SENSOR_UNITS_NOT_SPECIFIED 0x00
#define HID_USAGE_SENSOR_UNITS_LUX 0x01
diff --git a/include/linux/iio/buffer.h b/include/linux/iio/buffer.h
index f3eea18fdf4..2bac0eb8948 100644
--- a/include/linux/iio/buffer.h
+++ b/include/linux/iio/buffer.h
@@ -103,19 +103,6 @@ int iio_update_buffers(struct iio_dev *indio_dev,
**/
void iio_buffer_init(struct iio_buffer *buffer);
-/**
- * __iio_update_buffer() - update common elements of buffers
- * @buffer: buffer that is the event source
- * @bytes_per_datum: size of individual datum including timestamp
- * @length: number of datums in buffer
- **/
-static inline void __iio_update_buffer(struct iio_buffer *buffer,
- int bytes_per_datum, int length)
-{
- buffer->bytes_per_datum = bytes_per_datum;
- buffer->length = length;
-}
-
int iio_scan_mask_query(struct iio_dev *indio_dev,
struct iio_buffer *buffer, int bit);
diff --git a/include/linux/iio/common/st_sensors.h b/include/linux/iio/common/st_sensors.h
new file mode 100644
index 00000000000..1f86a97ab2e
--- /dev/null
+++ b/include/linux/iio/common/st_sensors.h
@@ -0,0 +1,280 @@
+/*
+ * STMicroelectronics sensors library driver
+ *
+ * Copyright 2012-2013 STMicroelectronics Inc.
+ *
+ * Denis Ciocca <denis.ciocca@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#ifndef ST_SENSORS_H
+#define ST_SENSORS_H
+
+#include <linux/i2c.h>
+#include <linux/spi/spi.h>
+#include <linux/irqreturn.h>
+#include <linux/iio/trigger.h>
+
+#define ST_SENSORS_TX_MAX_LENGTH 2
+#define ST_SENSORS_RX_MAX_LENGTH 6
+
+#define ST_SENSORS_ODR_LIST_MAX 10
+#define ST_SENSORS_FULLSCALE_AVL_MAX 10
+
+#define ST_SENSORS_NUMBER_ALL_CHANNELS 4
+#define ST_SENSORS_NUMBER_DATA_CHANNELS 3
+#define ST_SENSORS_ENABLE_ALL_AXIS 0x07
+#define ST_SENSORS_BYTE_FOR_CHANNEL 2
+#define ST_SENSORS_SCAN_X 0
+#define ST_SENSORS_SCAN_Y 1
+#define ST_SENSORS_SCAN_Z 2
+#define ST_SENSORS_DEFAULT_12_REALBITS 12
+#define ST_SENSORS_DEFAULT_16_REALBITS 16
+#define ST_SENSORS_DEFAULT_POWER_ON_VALUE 0x01
+#define ST_SENSORS_DEFAULT_POWER_OFF_VALUE 0x00
+#define ST_SENSORS_DEFAULT_WAI_ADDRESS 0x0f
+#define ST_SENSORS_DEFAULT_AXIS_ADDR 0x20
+#define ST_SENSORS_DEFAULT_AXIS_MASK 0x07
+#define ST_SENSORS_DEFAULT_AXIS_N_BIT 3
+
+#define ST_SENSORS_MAX_NAME 17
+#define ST_SENSORS_MAX_4WAI 7
+
+#define ST_SENSORS_LSM_CHANNELS(device_type, index, mod, endian, bits, addr) \
+{ \
+ .type = device_type, \
+ .modified = 1, \
+ .info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT | \
+ IIO_CHAN_INFO_SCALE_SEPARATE_BIT, \
+ .scan_index = index, \
+ .channel2 = mod, \
+ .address = addr, \
+ .scan_type = { \
+ .sign = 's', \
+ .realbits = bits, \
+ .shift = 16 - bits, \
+ .storagebits = 16, \
+ .endianness = endian, \
+ }, \
+}
+
+#define ST_SENSOR_DEV_ATTR_SAMP_FREQ() \
+ IIO_DEV_ATTR_SAMP_FREQ(S_IWUSR | S_IRUGO, \
+ st_sensors_sysfs_get_sampling_frequency, \
+ st_sensors_sysfs_set_sampling_frequency)
+
+#define ST_SENSORS_DEV_ATTR_SAMP_FREQ_AVAIL() \
+ IIO_DEV_ATTR_SAMP_FREQ_AVAIL( \
+ st_sensors_sysfs_sampling_frequency_avail)
+
+#define ST_SENSORS_DEV_ATTR_SCALE_AVAIL(name) \
+ IIO_DEVICE_ATTR(name, S_IRUGO, \
+ st_sensors_sysfs_scale_avail, NULL , 0);
+
+struct st_sensor_odr_avl {
+ unsigned int hz;
+ u8 value;
+};
+
+struct st_sensor_odr {
+ u8 addr;
+ u8 mask;
+ struct st_sensor_odr_avl odr_avl[ST_SENSORS_ODR_LIST_MAX];
+};
+
+struct st_sensor_power {
+ u8 addr;
+ u8 mask;
+ u8 value_off;
+ u8 value_on;
+};
+
+struct st_sensor_axis {
+ u8 addr;
+ u8 mask;
+};
+
+struct st_sensor_fullscale_avl {
+ unsigned int num;
+ u8 value;
+ unsigned int gain;
+ unsigned int gain2;
+};
+
+struct st_sensor_fullscale {
+ u8 addr;
+ u8 mask;
+ struct st_sensor_fullscale_avl fs_avl[ST_SENSORS_FULLSCALE_AVL_MAX];
+};
+
+/**
+ * struct st_sensor_bdu - ST sensor device block data update
+ * @addr: address of the register.
+ * @mask: mask to write the block data update flag.
+ */
+struct st_sensor_bdu {
+ u8 addr;
+ u8 mask;
+};
+
+/**
+ * struct st_sensor_data_ready_irq - ST sensor device data-ready interrupt
+ * @addr: address of the register.
+ * @mask: mask to write the on/off value.
+ * struct ig1 - represents the Interrupt Generator 1 of sensors.
+ * @en_addr: address of the enable ig1 register.
+ * @en_mask: mask to write the on/off value for enable.
+ */
+struct st_sensor_data_ready_irq {
+ u8 addr;
+ u8 mask;
+ struct {
+ u8 en_addr;
+ u8 en_mask;
+ } ig1;
+};
+
+/**
+ * struct st_sensor_transfer_buffer - ST sensor device I/O buffer
+ * @buf_lock: Mutex to protect rx and tx buffers.
+ * @tx_buf: Buffer used by SPI transfer function to send data to the sensors.
+ * This buffer is used to avoid DMA not-aligned issue.
+ * @rx_buf: Buffer used by SPI transfer to receive data from sensors.
+ * This buffer is used to avoid DMA not-aligned issue.
+ */
+struct st_sensor_transfer_buffer {
+ struct mutex buf_lock;
+ u8 rx_buf[ST_SENSORS_RX_MAX_LENGTH];
+ u8 tx_buf[ST_SENSORS_TX_MAX_LENGTH] ____cacheline_aligned;
+};
+
+/**
+ * struct st_sensor_transfer_function - ST sensor device I/O function
+ * @read_byte: Function used to read one byte.
+ * @write_byte: Function used to write one byte.
+ * @read_multiple_byte: Function used to read multiple byte.
+ */
+struct st_sensor_transfer_function {
+ int (*read_byte) (struct st_sensor_transfer_buffer *tb,
+ struct device *dev, u8 reg_addr, u8 *res_byte);
+ int (*write_byte) (struct st_sensor_transfer_buffer *tb,
+ struct device *dev, u8 reg_addr, u8 data);
+ int (*read_multiple_byte) (struct st_sensor_transfer_buffer *tb,
+ struct device *dev, u8 reg_addr, int len, u8 *data,
+ bool multiread_bit);
+};
+
+/**
+ * struct st_sensors - ST sensors list
+ * @wai: Contents of WhoAmI register.
+ * @sensors_supported: List of supported sensors by struct itself.
+ * @ch: IIO channels for the sensor.
+ * @odr: Output data rate register and ODR list available.
+ * @pw: Power register of the sensor.
+ * @enable_axis: Enable one or more axis of the sensor.
+ * @fs: Full scale register and full scale list available.
+ * @bdu: Block data update register.
+ * @drdy_irq: Data ready register of the sensor.
+ * @multi_read_bit: Use or not particular bit for [I2C/SPI] multi-read.
+ * @bootime: samples to discard when sensor passing from power-down to power-up.
+ */
+struct st_sensors {
+ u8 wai;
+ char sensors_supported[ST_SENSORS_MAX_4WAI][ST_SENSORS_MAX_NAME];
+ struct iio_chan_spec *ch;
+ struct st_sensor_odr odr;
+ struct st_sensor_power pw;
+ struct st_sensor_axis enable_axis;
+ struct st_sensor_fullscale fs;
+ struct st_sensor_bdu bdu;
+ struct st_sensor_data_ready_irq drdy_irq;
+ bool multi_read_bit;
+ unsigned int bootime;
+};
+
+/**
+ * struct st_sensor_data - ST sensor device status
+ * @dev: Pointer to instance of struct device (I2C or SPI).
+ * @trig: The trigger in use by the core driver.
+ * @sensor: Pointer to the current sensor struct in use.
+ * @current_fullscale: Maximum range of measure by the sensor.
+ * @enabled: Status of the sensor (false->off, true->on).
+ * @multiread_bit: Use or not particular bit for [I2C/SPI] multiread.
+ * @buffer_data: Data used by buffer part.
+ * @odr: Output data rate of the sensor [Hz].
+ * @get_irq_data_ready: Function to get the IRQ used for data ready signal.
+ * @tf: Transfer function structure used by I/O operations.
+ * @tb: Transfer buffers and mutex used by I/O operations.
+ */
+struct st_sensor_data {
+ struct device *dev;
+ struct iio_trigger *trig;
+ struct st_sensors *sensor;
+ struct st_sensor_fullscale_avl *current_fullscale;
+
+ bool enabled;
+ bool multiread_bit;
+
+ char *buffer_data;
+
+ unsigned int odr;
+
+ unsigned int (*get_irq_data_ready) (struct iio_dev *indio_dev);
+
+ const struct st_sensor_transfer_function *tf;
+ struct st_sensor_transfer_buffer tb;
+};
+
+#ifdef CONFIG_IIO_BUFFER
+int st_sensors_allocate_trigger(struct iio_dev *indio_dev,
+ const struct iio_trigger_ops *trigger_ops);
+
+void st_sensors_deallocate_trigger(struct iio_dev *indio_dev);
+
+irqreturn_t st_sensors_trigger_handler(int irq, void *p);
+
+int st_sensors_get_buffer_element(struct iio_dev *indio_dev, u8 *buf);
+#else
+static inline int st_sensors_allocate_trigger(struct iio_dev *indio_dev,
+ const struct iio_trigger_ops *trigger_ops)
+{
+ return 0;
+}
+static inline void st_sensors_deallocate_trigger(struct iio_dev *indio_dev)
+{
+ return;
+}
+#endif
+
+int st_sensors_init_sensor(struct iio_dev *indio_dev);
+
+int st_sensors_set_enable(struct iio_dev *indio_dev, bool enable);
+
+int st_sensors_set_axis_enable(struct iio_dev *indio_dev, u8 axis_enable);
+
+int st_sensors_set_odr(struct iio_dev *indio_dev, unsigned int odr);
+
+int st_sensors_set_dataready_irq(struct iio_dev *indio_dev, bool enable);
+
+int st_sensors_set_fullscale_by_gain(struct iio_dev *indio_dev, int scale);
+
+int st_sensors_read_info_raw(struct iio_dev *indio_dev,
+ struct iio_chan_spec const *ch, int *val);
+
+int st_sensors_check_device_support(struct iio_dev *indio_dev,
+ int num_sensors_list, const struct st_sensors *sensors);
+
+ssize_t st_sensors_sysfs_get_sampling_frequency(struct device *dev,
+ struct device_attribute *attr, char *buf);
+
+ssize_t st_sensors_sysfs_set_sampling_frequency(struct device *dev,
+ struct device_attribute *attr, const char *buf, size_t size);
+
+ssize_t st_sensors_sysfs_sampling_frequency_avail(struct device *dev,
+ struct device_attribute *attr, char *buf);
+
+ssize_t st_sensors_sysfs_scale_avail(struct device *dev,
+ struct device_attribute *attr, char *buf);
+
+#endif /* ST_SENSORS_H */
diff --git a/include/linux/iio/common/st_sensors_i2c.h b/include/linux/iio/common/st_sensors_i2c.h
new file mode 100644
index 00000000000..67d845385ae
--- /dev/null
+++ b/include/linux/iio/common/st_sensors_i2c.h
@@ -0,0 +1,20 @@
+/*
+ * STMicroelectronics sensors i2c library driver
+ *
+ * Copyright 2012-2013 STMicroelectronics Inc.
+ *
+ * Denis Ciocca <denis.ciocca@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#ifndef ST_SENSORS_I2C_H
+#define ST_SENSORS_I2C_H
+
+#include <linux/i2c.h>
+#include <linux/iio/common/st_sensors.h>
+
+void st_sensors_i2c_configure(struct iio_dev *indio_dev,
+ struct i2c_client *client, struct st_sensor_data *sdata);
+
+#endif /* ST_SENSORS_I2C_H */
diff --git a/include/linux/iio/common/st_sensors_spi.h b/include/linux/iio/common/st_sensors_spi.h
new file mode 100644
index 00000000000..d964a3563dc
--- /dev/null
+++ b/include/linux/iio/common/st_sensors_spi.h
@@ -0,0 +1,20 @@
+/*
+ * STMicroelectronics sensors spi library driver
+ *
+ * Copyright 2012-2013 STMicroelectronics Inc.
+ *
+ * Denis Ciocca <denis.ciocca@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#ifndef ST_SENSORS_SPI_H
+#define ST_SENSORS_SPI_H
+
+#include <linux/spi/spi.h>
+#include <linux/iio/common/st_sensors.h>
+
+void st_sensors_spi_configure(struct iio_dev *indio_dev,
+ struct spi_device *spi, struct st_sensor_data *sdata);
+
+#endif /* ST_SENSORS_SPI_H */
diff --git a/include/linux/iio/consumer.h b/include/linux/iio/consumer.h
index 16c35ac045b..833926c91aa 100644
--- a/include/linux/iio/consumer.h
+++ b/include/linux/iio/consumer.h
@@ -15,6 +15,7 @@
struct iio_dev;
struct iio_chan_spec;
+struct device;
/**
* struct iio_channel - everything needed for a consumer to use a channel
@@ -30,14 +31,15 @@ struct iio_channel {
/**
* iio_channel_get() - get description of all that is needed to access channel.
- * @name: Unique name of the device as provided in the iio_map
+ * @dev: Pointer to consumer device. Device name must match
+ * the name of the device as provided in the iio_map
* with which the desired provider to consumer mapping
* was registered.
* @consumer_channel: Unique name to identify the channel on the consumer
* side. This typically describes the channels use within
* the consumer. E.g. 'battery_voltage'
*/
-struct iio_channel *iio_channel_get(const char *name,
+struct iio_channel *iio_channel_get(struct device *dev,
const char *consumer_channel);
/**
@@ -48,14 +50,14 @@ void iio_channel_release(struct iio_channel *chan);
/**
* iio_channel_get_all() - get all channels associated with a client
- * @name: name of consumer device.
+ * @dev: Pointer to consumer device.
*
* Returns an array of iio_channel structures terminated with one with
* null iio_dev pointer.
* This function is used by fairly generic consumers to get all the
* channels registered as having this consumer.
*/
-struct iio_channel *iio_channel_get_all(const char *name);
+struct iio_channel *iio_channel_get_all(struct device *dev);
/**
* iio_channel_release_all() - reverse iio_channel_get_all
@@ -66,7 +68,7 @@ void iio_channel_release_all(struct iio_channel *chan);
struct iio_cb_buffer;
/**
* iio_channel_get_all_cb() - register callback for triggered capture
- * @name: Name of client device.
+ * @dev: Pointer to client device.
* @cb: Callback function.
* @private: Private data passed to callback.
*
@@ -74,7 +76,7 @@ struct iio_cb_buffer;
* So if the channels requested come from different devices this will
* fail.
*/
-struct iio_cb_buffer *iio_channel_get_all_cb(const char *name,
+struct iio_cb_buffer *iio_channel_get_all_cb(struct device *dev,
int (*cb)(u8 *data,
void *private),
void *private);
diff --git a/include/linux/iio/driver.h b/include/linux/iio/driver.h
index a4f8b2e05af..7dfb10ee266 100644
--- a/include/linux/iio/driver.h
+++ b/include/linux/iio/driver.h
@@ -22,13 +22,10 @@ int iio_map_array_register(struct iio_dev *indio_dev,
struct iio_map *map);
/**
- * iio_map_array_unregister() - tell the core to remove consumer mappings
+ * iio_map_array_unregister() - tell the core to remove consumer mappings for
+ * the given provider device
* @indio_dev: provider device
- * @map: array of mappings to remove. Note these must have same memory
- * addresses as those originally added not just equal parameter
- * values.
*/
-int iio_map_array_unregister(struct iio_dev *indio_dev,
- struct iio_map *map);
+int iio_map_array_unregister(struct iio_dev *indio_dev);
#endif
diff --git a/include/linux/iio/gyro/itg3200.h b/include/linux/iio/gyro/itg3200.h
new file mode 100644
index 00000000000..c53f16914b7
--- /dev/null
+++ b/include/linux/iio/gyro/itg3200.h
@@ -0,0 +1,154 @@
+/*
+ * itg3200.h -- support InvenSense ITG3200
+ * Digital 3-Axis Gyroscope driver
+ *
+ * Copyright (c) 2011 Christian Strobel <christian.strobel@iis.fraunhofer.de>
+ * Copyright (c) 2011 Manuel Stahl <manuel.stahl@iis.fraunhofer.de>
+ * Copyright (c) 2012 Thorsten Nowak <thorsten.nowak@iis.fraunhofer.de>
+ *
+ * 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.
+ */
+
+#ifndef I2C_ITG3200_H_
+#define I2C_ITG3200_H_
+
+#include <linux/iio/iio.h>
+
+/* Register with I2C address (34h) */
+#define ITG3200_REG_ADDRESS 0x00
+
+/* Sample rate divider
+ * Range: 0 to 255
+ * Default value: 0x00 */
+#define ITG3200_REG_SAMPLE_RATE_DIV 0x15
+
+/* Digital low pass filter settings */
+#define ITG3200_REG_DLPF 0x16
+/* DLPF full scale range */
+#define ITG3200_DLPF_FS_SEL_2000 0x18
+/* Bandwidth (Hz) and internal sample rate
+ * (kHz) of DLPF */
+#define ITG3200_DLPF_256_8 0x00
+#define ITG3200_DLPF_188_1 0x01
+#define ITG3200_DLPF_98_1 0x02
+#define ITG3200_DLPF_42_1 0x03
+#define ITG3200_DLPF_20_1 0x04
+#define ITG3200_DLPF_10_1 0x05
+#define ITG3200_DLPF_5_1 0x06
+
+#define ITG3200_DLPF_CFG_MASK 0x07
+
+/* Configuration for interrupt operations */
+#define ITG3200_REG_IRQ_CONFIG 0x17
+/* Logic level */
+#define ITG3200_IRQ_ACTIVE_LOW 0x80
+#define ITG3200_IRQ_ACTIVE_HIGH 0x00
+/* Drive type */
+#define ITG3200_IRQ_OPEN_DRAIN 0x40
+#define ITG3200_IRQ_PUSH_PULL 0x00
+/* Latch mode */
+#define ITG3200_IRQ_LATCH_UNTIL_CLEARED 0x20
+#define ITG3200_IRQ_LATCH_50US_PULSE 0x00
+/* Latch clear method */
+#define ITG3200_IRQ_LATCH_CLEAR_ANY 0x10
+#define ITG3200_IRQ_LATCH_CLEAR_STATUS 0x00
+/* Enable interrupt when device is ready */
+#define ITG3200_IRQ_DEVICE_RDY_ENABLE 0x04
+/* Enable interrupt when data is available */
+#define ITG3200_IRQ_DATA_RDY_ENABLE 0x01
+
+/* Determine the status of ITG-3200 interrupts */
+#define ITG3200_REG_IRQ_STATUS 0x1A
+/* Status of 'device is ready'-interrupt */
+#define ITG3200_IRQ_DEVICE_RDY_STATUS 0x04
+/* Status of 'data is available'-interrupt */
+#define ITG3200_IRQ_DATA_RDY_STATUS 0x01
+
+/* Sensor registers */
+#define ITG3200_REG_TEMP_OUT_H 0x1B
+#define ITG3200_REG_TEMP_OUT_L 0x1C
+#define ITG3200_REG_GYRO_XOUT_H 0x1D
+#define ITG3200_REG_GYRO_XOUT_L 0x1E
+#define ITG3200_REG_GYRO_YOUT_H 0x1F
+#define ITG3200_REG_GYRO_YOUT_L 0x20
+#define ITG3200_REG_GYRO_ZOUT_H 0x21
+#define ITG3200_REG_GYRO_ZOUT_L 0x22
+
+/* Power management */
+#define ITG3200_REG_POWER_MANAGEMENT 0x3E
+/* Reset device and internal registers to the
+ * power-up-default settings */
+#define ITG3200_RESET 0x80
+/* Enable low power sleep mode */
+#define ITG3200_SLEEP 0x40
+/* Put according gyroscope in standby mode */
+#define ITG3200_STANDBY_GYRO_X 0x20
+#define ITG3200_STANDBY_GYRO_Y 0x10
+#define ITG3200_STANDBY_GYRO_Z 0x08
+/* Determine the device clock source */
+#define ITG3200_CLK_INTERNAL 0x00
+#define ITG3200_CLK_GYRO_X 0x01
+#define ITG3200_CLK_GYRO_Y 0x02
+#define ITG3200_CLK_GYRO_Z 0x03
+#define ITG3200_CLK_EXT_32K 0x04
+#define ITG3200_CLK_EXT_19M 0x05
+
+
+/**
+ * struct itg3200 - device instance specific data
+ * @i2c: actual i2c_client
+ * @trig: data ready trigger from itg3200 pin
+ **/
+struct itg3200 {
+ struct i2c_client *i2c;
+ struct iio_trigger *trig;
+};
+
+enum ITG3200_SCAN_INDEX {
+ ITG3200_SCAN_TEMP,
+ ITG3200_SCAN_GYRO_X,
+ ITG3200_SCAN_GYRO_Y,
+ ITG3200_SCAN_GYRO_Z,
+ ITG3200_SCAN_ELEMENTS,
+};
+
+int itg3200_write_reg_8(struct iio_dev *indio_dev,
+ u8 reg_address, u8 val);
+
+int itg3200_read_reg_8(struct iio_dev *indio_dev,
+ u8 reg_address, u8 *val);
+
+
+#ifdef CONFIG_IIO_BUFFER
+
+void itg3200_remove_trigger(struct iio_dev *indio_dev);
+int itg3200_probe_trigger(struct iio_dev *indio_dev);
+
+int itg3200_buffer_configure(struct iio_dev *indio_dev);
+void itg3200_buffer_unconfigure(struct iio_dev *indio_dev);
+
+#else /* CONFIG_IIO_BUFFER */
+
+static inline void itg3200_remove_trigger(struct iio_dev *indio_dev)
+{
+}
+
+static inline int itg3200_probe_trigger(struct iio_dev *indio_dev)
+{
+ return 0;
+}
+
+static inline int itg3200_buffer_configure(struct iio_dev *indio_dev)
+{
+ return 0;
+}
+
+static inline void itg3200_buffer_unconfigure(struct iio_dev *indio_dev)
+{
+}
+
+#endif /* CONFIG_IIO_RING_BUFFER */
+
+#endif /* ITG3200_H_ */
diff --git a/include/linux/iio/trigger.h b/include/linux/iio/trigger.h
index 20239da1d0f..c66e0a96f6e 100644
--- a/include/linux/iio/trigger.h
+++ b/include/linux/iio/trigger.h
@@ -12,6 +12,7 @@
#ifndef _IIO_TRIGGER_H_
#define _IIO_TRIGGER_H_
+#ifdef CONFIG_IIO_TRIGGER
struct iio_subirq {
bool enabled;
};
@@ -117,4 +118,8 @@ irqreturn_t iio_trigger_generic_data_rdy_poll(int irq, void *private);
__printf(1, 2) struct iio_trigger *iio_trigger_alloc(const char *fmt, ...);
void iio_trigger_free(struct iio_trigger *trig);
+#else
+struct iio_trigger;
+struct iio_trigger_ops;
+#endif
#endif /* _IIO_TRIGGER_H_ */
diff --git a/include/linux/pci_ids.h b/include/linux/pci_ids.h
index 907e7e56fa4..6938ccfa42d 100644
--- a/include/linux/pci_ids.h
+++ b/include/linux/pci_ids.h
@@ -1807,6 +1807,8 @@
#define PCI_VENDOR_ID_ESDGMBH 0x12fe
#define PCI_DEVICE_ID_ESDGMBH_CPCIASIO4 0x0111
+#define PCI_VENDOR_ID_CB 0x1307 /* Measurement Computing */
+
#define PCI_VENDOR_ID_SIIG 0x131f
#define PCI_SUBVENDOR_ID_SIIG 0x131f
#define PCI_DEVICE_ID_SIIG_1S_10x_550 0x1000
@@ -2013,6 +2015,10 @@
#define PCI_DEVICE_ID_CMEDIA_CM8738 0x0111
#define PCI_DEVICE_ID_CMEDIA_CM8738B 0x0112
+#define PCI_VENDOR_ID_ADVANTECH 0x13fe
+
+#define PCI_VENDOR_ID_MEILHAUS 0x1402
+
#define PCI_VENDOR_ID_LAVA 0x1407
#define PCI_DEVICE_ID_LAVA_DSERIAL 0x0100 /* 2x 16550 */
#define PCI_DEVICE_ID_LAVA_QUATRO_A 0x0101 /* 2x 16550, half of 4 port */
@@ -2058,6 +2064,8 @@
#define PCI_VENDOR_ID_CHELSIO 0x1425
+#define PCI_VENDOR_ID_ADLINK 0x144a
+
#define PCI_VENDOR_ID_SAMSUNG 0x144d
#define PCI_VENDOR_ID_GIGABYTE 0x1458
@@ -2091,6 +2099,8 @@
#define PCI_DEVICE_ID_AFAVLAB_P030 0x2182
#define PCI_SUBDEVICE_ID_AFAVLAB_P061 0x2150
+#define PCI_VENDOR_ID_AMPLICON 0x14dc
+
#define PCI_VENDOR_ID_BCM_GVC 0x14a4
#define PCI_VENDOR_ID_BROADCOM 0x14e4
#define PCI_DEVICE_ID_TIGON3_5752 0x1600
diff --git a/include/linux/platform_data/invensense_mpu6050.h b/include/linux/platform_data/invensense_mpu6050.h
new file mode 100644
index 00000000000..ad3aa7b95f3
--- /dev/null
+++ b/include/linux/platform_data/invensense_mpu6050.h
@@ -0,0 +1,31 @@
+/*
+* Copyright (C) 2012 Invensense, Inc.
+*
+* This software is licensed under the terms of the GNU General Public
+* License version 2, as published by the Free Software Foundation, and
+* may be copied, distributed, and modified under those terms.
+*
+* This program is distributed in the hope that it will be useful,
+* but WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
+*/
+
+#ifndef __INV_MPU6050_PLATFORM_H_
+#define __INV_MPU6050_PLATFORM_H_
+
+/**
+ * struct inv_mpu6050_platform_data - Platform data for the mpu driver
+ * @orientation: Orientation matrix of the chip
+ *
+ * Contains platform specific information on how to configure the MPU6050 to
+ * work on this platform. The orientation matricies are 3x3 rotation matricies
+ * that are applied to the data to rotate from the mounting orientation to the
+ * platform orientation. The values must be one of 0, 1, or -1 and each row and
+ * column should have exactly 1 non-zero value.
+ */
+struct inv_mpu6050_platform_data {
+ __s8 orientation[9];
+};
+
+#endif
diff --git a/include/linux/platform_data/tsl2563.h b/include/linux/platform_data/tsl2563.h
new file mode 100644
index 00000000000..c90d7a09dda
--- /dev/null
+++ b/include/linux/platform_data/tsl2563.h
@@ -0,0 +1,8 @@
+#ifndef __LINUX_TSL2563_H
+#define __LINUX_TSL2563_H
+
+struct tsl2563_platform_data {
+ int cover_comp_gain;
+};
+
+#endif /* __LINUX_TSL2563_H */
diff --git a/include/linux/spi/spi.h b/include/linux/spi/spi.h
index 30e9c50a5e2..38c2b925923 100644
--- a/include/linux/spi/spi.h
+++ b/include/linux/spi/spi.h
@@ -596,6 +596,26 @@ spi_transfer_del(struct spi_transfer *t)
list_del(&t->transfer_list);
}
+/**
+ * spi_message_init_with_transfers - Initialize spi_message and append transfers
+ * @m: spi_message to be initialized
+ * @xfers: An array of spi transfers
+ * @num_xfers: Number of items in the xfer array
+ *
+ * This function initializes the given spi_message and adds each spi_transfer in
+ * the given array to the message.
+ */
+static inline void
+spi_message_init_with_transfers(struct spi_message *m,
+struct spi_transfer *xfers, unsigned int num_xfers)
+{
+ unsigned int i;
+
+ spi_message_init(m);
+ for (i = 0; i < num_xfers; ++i)
+ spi_message_add_tail(&xfers[i], m);
+}
+
/* It's fine to embed message and transaction structures in other data
* structures so long as you don't free them while they're in use.
*/
@@ -688,6 +708,30 @@ spi_read(struct spi_device *spi, void *buf, size_t len)
return spi_sync(spi, &m);
}
+/**
+ * spi_sync_transfer - synchronous SPI data transfer
+ * @spi: device with which data will be exchanged
+ * @xfers: An array of spi_transfers
+ * @num_xfers: Number of items in the xfer array
+ * Context: can sleep
+ *
+ * Does a synchronous SPI data transfer of the given spi_transfer array.
+ *
+ * For more specific semantics see spi_sync().
+ *
+ * It returns zero on success, else a negative error code.
+ */
+static inline int
+spi_sync_transfer(struct spi_device *spi, struct spi_transfer *xfers,
+ unsigned int num_xfers)
+{
+ struct spi_message msg;
+
+ spi_message_init_with_transfers(&msg, xfers, num_xfers);
+
+ return spi_sync(spi, &msg);
+}
+
/* this copies txbuf and rxbuf data; for small transfers only! */
extern int spi_write_then_read(struct spi_device *spi,
const void *txbuf, unsigned n_tx,