diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index 90714ab8d8..02cce0600a 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -23,13 +23,6 @@ config SENSORS_AS5048B ---help--- Enable driver support for the AMS AS5048B magnetic rotary encoder. -config SENSOR_BH1749NUC - bool "Rohm BH1749NUC Color Sensor" - default n - select I2C - ---help--- - Enable driver for BH1749NUC color sensor. - config SENSORS_BH1750FVI bool "Rohm BH1750FVI Ambient Light Sensor support" default n @@ -42,13 +35,6 @@ config BH1750FVI_I2C_FREQUENCY default 400000 depends on SENSORS_BH1750FVI -config SENSOR_BH1790GLC - bool "Rohm BH1790GLC Heartrate sensor" - default n - select I2C - ---help--- - Enable driver for BH1790GLC Heartrate sensor. - config SENSORS_BMG160 bool "Bosch BMG160 Gyroscope Sensor support" default n @@ -133,13 +119,6 @@ config KXTJ9_I2C_BUS_SPEED endif # SENSORS_KXTJ9 -config SENSOR_KX224 - bool "Kionix KX224 Acceleration Sensor" - default n - select I2C - ---help--- - Enable driver for the Kionix KX224 acceleration sensor. - config SENSORS_LIS2DH bool "STMicro LIS2DH device support" default n diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index b26e4deab5..e94e397bcc 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -49,14 +49,6 @@ endif ifeq ($(CONFIG_I2C),y) -ifeq ($(CONFIG_SENSOR_BH1749NUC),y) - CSRCS += bh1749nuc.c -endif - -ifeq ($(CONFIG_SENSOR_BH1790GLC),y) - CSRCS += bh1790glc.c -endif - ifeq ($(CONFIG_SENSORS_APDS9960),y) CSRCS += apds9960.c endif @@ -69,10 +61,6 @@ ifeq ($(CONFIG_SENSORS_KXTJ9),y) CSRCS += kxtj9.c endif -ifeq ($(CONFIG_SENSOR_KX224),y) - CSRCS += kx224.c -endif - ifeq ($(CONFIG_SENSORS_LIS2DH),y) CSRCS += lis2dh.c endif diff --git a/drivers/sensors/bh1749nuc.c b/drivers/sensors/bh1749nuc.c deleted file mode 100644 index cd10c849ff..0000000000 --- a/drivers/sensors/bh1749nuc.c +++ /dev/null @@ -1,527 +0,0 @@ -/**************************************************************************** - * drivers/sensors/bh1749nuc.c - * - * Copyright (C) 2018 Sony Corporation - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor Sony nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(CONFIG_I2C) && defined(CONFIG_BH1749NUC) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define BH1749NUC_ADDR 0x39 /* I2C Slave Address */ -#define BH1749NUC_MANUFACTID 0xE0 /* Manufact ID */ -#define BH1749NUC_PARTID 0x0D /* Part ID */ -#define BH1749NUC_BYTESPERSAMPLE 8 -#define BH1749NUC_ELEMENTSIZE 0 - -/* BH1749NUC Registers */ - -#define BH1749NUC_SYSTEM_CONTROL 0x40 -#define BH1749NUC_MODE_CONTROL1 0x41 -#define BH1749NUC_MODE_CONTROL2 0x42 -#define BH1749NUC_MODE_CONTROL3 0x44 -#define BH1749NUC_RED_DATA_LSB 0x50 -#define BH1749NUC_MANUFACTURER_ID 0x92 - -/* Register SYSTEM_CONTROL */ -#define BH1749NUC_SYSTEM_CONTROL_SW_RESET (1 << 7) -#define BH1749NUC_SYSTEM_CONTROL_INT_RESET (1 << 6) - -/* Register MODE_CONTROL1 */ - -#define BH1749NUC_MODE_CONTROL1_MEAS_TIME160MS (0x00) - -/* Register MODE_CONTROL2 */ - -#define BH1749NUC_MODE_CONTROL2_ADC_GAIN_X1 (0) -#define BH1749NUC_MODE_CONTROL2_ADC_GAIN_X2 (1) -#define BH1749NUC_MODE_CONTROL2_ADC_GAIN_X16 (2) -#define BH1749NUC_MODE_CONTROL2_RGBC_EN (1 << 4) - -/* Register MODE_CONTROL3 */ - -#define BH1749NUC_MODE_CONTROL3_VAL (0x02) - -#ifndef itemsof -# define itemsof(array) (sizeof(array)/sizeof(array[0])) -#endif - -/**************************************************************************** - * Private Type Definitions - ****************************************************************************/ -/** - * @brief Structure for bh1749nuc device - */ - -struct bh1749nuc_dev_s -{ - FAR struct i2c_master_s *i2c; /* I2C interface */ - uint8_t addr; /* I2C address */ - int port; /* I2C port */ - - struct seq_s *seq; /* Sequencer instance */ - int minor; /* Minor device number */ -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* Character driver methods */ - -static int bh1749nuc_open(FAR struct file *filep); -static int bh1749nuc_close(FAR struct file *filep); -static ssize_t bh1749nuc_read(FAR struct file *filep, FAR char *buffer, - size_t buflen); -static ssize_t bh1749nuc_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen); -static int bh1749nuc_ioctl(FAR struct file *filep, int cmd, unsigned long arg); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct file_operations g_bh1749nucfops = -{ - bh1749nuc_open, /* open */ - bh1749nuc_close, /* close */ - bh1749nuc_read, /* read */ - bh1749nuc_write, /* write */ - 0, /* seek */ - bh1749nuc_ioctl, /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - 0, /* poll */ -#endif - 0 /* unlink */ -}; - -/* Take color data. */ - -static const uint16_t g_bh1749nucinst[] = -{ - SCU_INST_SEND(BH1749NUC_RED_DATA_LSB), - SCU_INST_RECV(BH1749NUC_BYTESPERSAMPLE) | SCU_INST_LAST, -}; - -/* Reference count */ - -static int g_refcnt = 0; - -/* Sequencer instance */ - -static struct seq_s *g_seq = NULL; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ -/**************************************************************************** - * Name: bh1749nuc_getreg8 - * - * Description: - * Read from an 8-bit BH1749NUC register - * - ****************************************************************************/ - -static uint8_t bh1749nuc_getreg8(FAR struct bh1749nuc_dev_s *priv, - uint8_t regaddr) -{ - uint8_t regval; - uint16_t inst[2]; - - /* Send register to read and get the next byte */ - - inst[0] = SCU_INST_SEND(regaddr); - inst[1] = SCU_INST_RECV(1) | SCU_INST_LAST; - - scu_i2ctransfer(priv->port, priv->addr, inst, 2, ®val, 1); - - return regval; -} - -/**************************************************************************** - * Name: bh1749nuc_putreg8 - * - * Description: - * Write to an 8-bit BH1749NUC register - * - ****************************************************************************/ - -static void bh1749nuc_putreg8(FAR struct bh1749nuc_dev_s *priv, - uint8_t regaddr, uint8_t regval) -{ - uint16_t inst[2]; - - /* Send register address and set the value */ - - inst[0] = SCU_INST_SEND(regaddr); - inst[1] = SCU_INST_SEND(regval) | SCU_INST_LAST; - - scu_i2ctransfer(priv->port, priv->addr, inst, 2, NULL, 0); -} - -/**************************************************************************** - * Name: bh1749nuc_checkid - * - * Description: - * Read and verify the BH1749NUC chip ID - * - ****************************************************************************/ - -static int bh1749nuc_checkid(FAR struct bh1749nuc_dev_s *priv) -{ - uint8_t id; - - /* Read Manufact ID */ - - id = bh1749nuc_getreg8(priv, BH1749NUC_MANUFACTURER_ID); - - if (id != BH1749NUC_MANUFACTID) - { - /* Manufact ID is not Correct */ - - snerr("Wrong Manufact ID! %02x\n", id); - return -ENODEV; - } - - /* Read Part ID */ - - id = bh1749nuc_getreg8(priv, BH1749NUC_SYSTEM_CONTROL); - - if ((id & 0x3F) != BH1749NUC_PARTID) - { - /* Part ID is not Correct */ - - snerr("Wrong Part ID! %02x\n", id); - return -ENODEV; - } - - return OK; -} - -/**************************************************************************** - * Name: bh1749nuc_seqinit - * - * Description: - * Initialize SCU sequencer. - * - ****************************************************************************/ - -static int bh1749nuc_seqinit(FAR struct bh1749nuc_dev_s *priv) -{ - DEBUGASSERT(g_seq == NULL); - - /* Open sequencer */ - - g_seq = seq_open(SEQ_TYPE_NORMAL, SCU_BUS_I2C0); - if (!g_seq) - { - return -ENOENT; - } - priv->seq = g_seq; - - seq_setaddress(priv->seq, priv->addr); - - /* Set instruction and sample data information to sequencer */ - - seq_setinstruction(priv->seq, g_bh1749nucinst, itemsof(g_bh1749nucinst)); - seq_setsample(priv->seq, BH1749NUC_BYTESPERSAMPLE, 0, BH1749NUC_ELEMENTSIZE, - false); - - return OK; -} - -/**************************************************************************** - * Name: bh1749nuc_open - * - * Description: - * This function is called whenever the BH1749NUC device is opened. - * - ****************************************************************************/ - -static int bh1749nuc_open(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1749nuc_dev_s *priv = inode->i_private; - uint8_t val; - - if (g_refcnt == 0) - { - int ret; - - ret = bh1749nuc_seqinit(priv); - if (ret < 0) - { - return ret; - } - - /* MODE_CONTROL1 */ - - val = BH1749NUC_MODE_CONTROL1_MEAS_TIME160MS; - bh1749nuc_putreg8(priv, BH1749NUC_MODE_CONTROL1, val); - - /* MODE_CONTROL2 */ - val = BH1749NUC_MODE_CONTROL2_RGBC_EN | - BH1749NUC_MODE_CONTROL2_ADC_GAIN_X16; - bh1749nuc_putreg8(priv, BH1749NUC_MODE_CONTROL2, val); - - /* MODE_CONTROL3 */ - val = BH1749NUC_MODE_CONTROL3_VAL; - bh1749nuc_putreg8(priv, BH1749NUC_MODE_CONTROL3, val); - } - else - { - /* Set existing sequencer */ - - priv->seq = g_seq; - } - - g_refcnt++; - - return OK; -} - -/**************************************************************************** - * Name: bh1749nuc_close - * - * Description: - * This routine is called when the BH1749NUC device is closed. - * - ****************************************************************************/ - -static int bh1749nuc_close(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1749nuc_dev_s *priv = inode->i_private; - uint8_t val; - - g_refcnt--; - - (void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0); - - if (g_refcnt == 0) - { - /* stop sampling */ - - val = BH1749NUC_SYSTEM_CONTROL_SW_RESET | - BH1749NUC_SYSTEM_CONTROL_INT_RESET; - bh1749nuc_putreg8(priv, BH1749NUC_SYSTEM_CONTROL, val); - - seq_close(g_seq); - g_seq = NULL; - } - else - { - (void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0); - } - - return OK; -} - -/**************************************************************************** - * Name: bh1749nuc_read - ****************************************************************************/ - -static ssize_t bh1749nuc_read(FAR struct file *filep, FAR char *buffer, - size_t len) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1749nuc_dev_s *priv = inode->i_private; - - len = len / BH1749NUC_BYTESPERSAMPLE * BH1749NUC_BYTESPERSAMPLE; - len = seq_read(priv->seq, priv->minor, buffer, len); - - return len; -} - -/**************************************************************************** - * Name: bh1749nuc_write - ****************************************************************************/ - -static ssize_t bh1749nuc_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen) -{ - return -ENOSYS; -} - -/**************************************************************************** - * Name: bh1749nuc_ioctl - ****************************************************************************/ - -static int bh1749nuc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1749nuc_dev_s *priv = inode->i_private; - int ret = OK; - - switch (cmd) - { - default: - { - if (_SCUIOCVALID(cmd)) - { - /* Redirect SCU commands */ - - ret = seq_ioctl(priv->seq, priv->minor, cmd, arg); - } - else - { - snerr("Unrecognized cmd: %d\n", cmd); - ret = - ENOTTY; - } - } - break; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: bh1749nuc_init - * - * Description: - * Initialize the BH1749NUC device - * - * Input Parameters: - * i2c - An instance of the I2C interface to use to communicate with - * BH1749NUC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1749nuc_init(FAR struct i2c_master_s *i2c, int port) -{ - FAR struct bh1749nuc_dev_s tmp; - FAR struct bh1749nuc_dev_s *priv = &tmp; - int ret; - - /* Setup temporary device structure for initialization */ - - priv->i2c = i2c; - priv->addr = BH1749NUC_ADDR; - priv->port = port; - - /* Check Device ID */ - - ret = bh1749nuc_checkid(priv); - if (ret < 0) - { - snerr("Failed to register driver: %d\n", ret); - return ret; - } - - return OK; -} - -/**************************************************************************** - * Name: bh1749nuc_register - * - * Description: - * Register the BH1749NUC character device as 'devpath' - * - * Input Parameters: - * devpath - The full path to the driver to register. E.g., "/dev/color0" - * minor - minor device number - * i2c - An instance of the I2C interface to use to communicate with - * BH1749NUC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1749nuc_register(FAR const char *devpath, int minor, - FAR struct i2c_master_s *i2c, int port) -{ - FAR struct bh1749nuc_dev_s *priv; - char path[16]; - int ret; - - /* Initialize the BH1749NUC device structure */ - - priv = (FAR struct bh1749nuc_dev_s *) - kmm_malloc(sizeof(struct bh1749nuc_dev_s)); - if (!priv) - { - snerr("Failed to allocate instance\n"); - return -ENOMEM; - } - - priv->i2c = i2c; - priv->addr = BH1749NUC_ADDR; - priv->port = port; - priv->seq = NULL; - priv->minor = minor; - - /* Register the character driver */ - - (void) snprintf(path, sizeof(path), "%s%d", devpath, minor); - ret = register_driver(path, &g_bh1749nucfops, 0666, priv); - if (ret < 0) - { - snerr("Failed to register driver: %d\n", ret); - kmm_free(priv); - } - - sninfo("BH1749NUC driver loaded successfully!\n"); - - return ret; -} - -#endif /* CONFIG_I2C && CONFIG_BH1749NUC */ diff --git a/drivers/sensors/bh1790glc.c b/drivers/sensors/bh1790glc.c deleted file mode 100644 index d03d869931..0000000000 --- a/drivers/sensors/bh1790glc.c +++ /dev/null @@ -1,518 +0,0 @@ -/**************************************************************************** - * drivers/sensors/bh1790glc.c - * - * Copyright (C) 2016 Sony Corporation - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor Sony nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(CONFIG_I2C) && defined(CONFIG_BH1790GLC) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define BH1790GLC_ADDR 0x5B /* I2C Slave Address */ -#define BH1790GLC_MANUFACTID 0xE0 /* Manufact ID */ -#define BH1790GLC_PARTID 0x0D /* Part ID */ -#define BH1790GLC_BYTESPERSAMPLE 4 -#define BH1790GLC_ELEMENTSIZE 0 - -/* BH1790GLC Registers */ - -#define BH1790GLC_SYSTEM_CONTROL 0x40 -#define BH1790GLC_MEAS_CONTROL1 0x41 -#define BH1790GLC_MEAS_CONTROL1_VAL (BH1790GLC_MEAS_CONTROL1_RDY | BH1790GLC_MEAS_CONTROL1_LED_LIGHTING_FREQ_128HZ | BH1790GLC_MEAS_CONTROL1_RCYCLE_32HZ) -#define BH1790GLC_MEAS_CONTROL2_VAL (BH1790GLC_MEAS_CONTROL2_LED_EN_00 | BH1790GLC_MEAS_CONTROL2_LED_ON_TIME_0_3MS | BH1790GLC_MEAS_CONTROL2_LED_CURRENT_10MA) -#define BH1790GLC_DATAOUT_LEDOFF 0x54 -#define BH1790GLC_PART_ID 0x10 -#define BH1790GLC_MANUFACTURER_ID 0x0F - -#define BH1790GLC_MEAS_CONTROL1_RDY (1 << 7) -#define BH1790GLC_MEAS_CONTROL1_LED_LIGHTING_FREQ_128HZ (0 << 2) -#define BH1790GLC_MEAS_CONTROL1_RCYCLE_32HZ (2 << 0) -#define BH1790GLC_MEAS_CONTROL2_LED_EN_00 (0 << 6) -#define BH1790GLC_MEAS_CONTROL2_LED_ON_TIME_0_3MS (0 << 5) -#define BH1790GLC_MEAS_CONTROL2_LED_CURRENT_10MA (12 << 0) - -#define BH1790GLC_MEAS_START_MEAS_ST (1 << 0) - -/* Register SYSTEM_CONTROL */ -#define BH1790GLC_SYSTEM_CONTROL_SW_RESET (1 << 7) -#define BH1790GLC_SYSTEM_CONTROL_INT_RESET (1 << 6) - -#define BH1790GLC_MEAS_CONTROL1_MEAS_TIME160MS (0x00) - -#define BH1790GLC_MEAS_START_VAL (BH1790GLC_MEAS_START_MEAS_ST) - - -#ifndef itemsof -# define itemsof(array) (sizeof(array)/sizeof(array[0])) -#endif - -/**************************************************************************** - * Private Type Definitions - ****************************************************************************/ -/** - * @brief Structure for bh1790glc device - */ - -struct bh1790glc_dev_s -{ - FAR struct i2c_master_s *i2c; /* I2C interface */ - uint8_t addr; /* I2C address */ - int port; /* I2C port */ - - struct seq_s *seq; /* Sequencer instance */ - int minor; /* Minor device number */ -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* Character driver methods */ - -static int bh1790glc_open(FAR struct file *filep); -static int bh1790glc_close(FAR struct file *filep); -static ssize_t bh1790glc_read(FAR struct file *filep, FAR char *buffer, - size_t buflen); -static ssize_t bh1790glc_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen); -static int bh1790glc_ioctl(FAR struct file *filep, int cmd, unsigned long arg); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct file_operations g_bh1790glcfops = -{ - bh1790glc_open, /* open */ - bh1790glc_close, /* close */ - bh1790glc_read, /* read */ - bh1790glc_write, /* write */ - 0, /* seek */ - bh1790glc_ioctl, /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - 0, /* poll */ -#endif - 0 /* unlink */ -}; - -static const uint16_t g_bh1790glcinst[] = -{ - SCU_INST_SEND(BH1790GLC_DATAOUT_LEDOFF), - SCU_INST_RECV(BH1790GLC_BYTESPERSAMPLE) | SCU_INST_LAST, -}; - -/* Reference count */ - -static int g_refcnt = 0; - -/* Sequencer instance */ - -static struct seq_s *g_seq = NULL; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ -/**************************************************************************** - * Name: bh1790glc_getreg8 - * - * Description: - * Read from an 8-bit BH1790GLC register - * - ****************************************************************************/ - -static uint8_t bh1790glc_getreg8(FAR struct bh1790glc_dev_s *priv, - uint8_t regaddr) -{ - uint8_t regval; - uint16_t inst[2]; - - /* Send register to read and get the next byte */ - - inst[0] = SCU_INST_SEND(regaddr); - inst[1] = SCU_INST_RECV(1) | SCU_INST_LAST; - - scu_i2ctransfer(priv->port, priv->addr, inst, 2, ®val, 1); - - return regval; -} - -/**************************************************************************** - * Name: bh1790glc_putreg8 - * - * Description: - * Write to an 8-bit BH1790GLC register - * - ****************************************************************************/ - -static void bh1790glc_putreg8(FAR struct bh1790glc_dev_s *priv, - uint8_t regaddr, uint8_t regval) -{ - uint16_t inst[2]; - - /* Send register address and set the value */ - - inst[0] = SCU_INST_SEND(regaddr); - inst[1] = SCU_INST_SEND(regval) | SCU_INST_LAST; - - scu_i2ctransfer(priv->port, priv->addr, inst, 2, NULL, 0); -} - -/**************************************************************************** - * Name: bh1790glc_checkid - * - * Description: - * Read and verify the BH1790GLC chip ID - * - ****************************************************************************/ - -static int bh1790glc_checkid(FAR struct bh1790glc_dev_s *priv) -{ - uint8_t id; - - /* Read Manufact ID */ - - id = bh1790glc_getreg8(priv, BH1790GLC_MANUFACTURER_ID); - - if (id != BH1790GLC_MANUFACTID) - { - /* Manufact ID is not Correct */ - - snerr("Wrong Manufact ID! %02x\n", id); - return -ENODEV; - } - - /* Read Part ID */ - - id = bh1790glc_getreg8(priv, BH1790GLC_PART_ID); - - if ((id & 0x3F) != BH1790GLC_PARTID) - { - /* Part ID is not Correct */ - - snerr("Wrong Part ID! %02x\n", id); - return -ENODEV; - } - - return OK; -} - -/**************************************************************************** - * Name: bh1790glc_seqinit - * - * Description: - * Initialize SCU sequencer. - * - ****************************************************************************/ - -static int bh1790glc_seqinit(FAR struct bh1790glc_dev_s *priv) -{ - DEBUGASSERT(g_seq == NULL); - - /* Open sequencer */ - - g_seq = seq_open(SEQ_TYPE_NORMAL, SCU_BUS_I2C0); - if (!g_seq) - { - return -ENOENT; - } - priv->seq = g_seq; - - seq_setaddress(priv->seq, priv->addr); - - /* Set instruction and sample data information to sequencer */ - - seq_setinstruction(priv->seq, g_bh1790glcinst, itemsof(g_bh1790glcinst)); - seq_setsample(priv->seq, BH1790GLC_BYTESPERSAMPLE, 0, BH1790GLC_ELEMENTSIZE, - false); - - return OK; -} - -/**************************************************************************** - * Name: bh1790glc_open - * - * Description: - * This function is called whenever the BH1790GLC device is opened. - * - ****************************************************************************/ - -static int bh1790glc_open(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1790glc_dev_s *priv = inode->i_private; - unsigned char val[3]; - - if (g_refcnt == 0) - { - int ret; - - ret = bh1790glc_seqinit(priv); - if (ret < 0) - { - return ret; - } - - //Brute force solution to write BH1790GLC MEAS_CONTROL1-MEAS_START registers - - bh1790glc_putreg8(priv, 0x41, 130); - bh1790glc_putreg8(priv, 0x42, 12); - bh1790glc_putreg8(priv, 0x43, 1); - - } - else - { - /* Set existing sequencer */ - - priv->seq = g_seq; - } - - g_refcnt++; - - return OK; -} - -/**************************************************************************** - * Name: bh1790glc_close - * - * Description: - * This routine is called when the BH1790GLC device is closed. - * - ****************************************************************************/ - -static int bh1790glc_close(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1790glc_dev_s *priv = inode->i_private; - uint8_t val; - - g_refcnt--; - - (void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0); - - if (g_refcnt == 0) - { - /* stop sampling */ - - val = BH1790GLC_SYSTEM_CONTROL_SW_RESET | - BH1790GLC_SYSTEM_CONTROL_INT_RESET; - bh1790glc_putreg8(priv, BH1790GLC_SYSTEM_CONTROL, val); - - seq_close(g_seq); - g_seq = NULL; - } - else - { - (void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0); - } - - return OK; -} - -/**************************************************************************** - * Name: bh1790glc_read - ****************************************************************************/ - -static ssize_t bh1790glc_read(FAR struct file *filep, FAR char *buffer, - size_t len) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1790glc_dev_s *priv = inode->i_private; - - len = len / BH1790GLC_BYTESPERSAMPLE * BH1790GLC_BYTESPERSAMPLE; - len = seq_read(priv->seq, priv->minor, buffer, len); - - return len; -} - -/**************************************************************************** - * Name: bh1790glc_write - ****************************************************************************/ - -static ssize_t bh1790glc_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen) -{ - return -ENOSYS; -} - -/**************************************************************************** - * Name: bh1790glc_ioctl - ****************************************************************************/ - -static int bh1790glc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct bh1790glc_dev_s *priv = inode->i_private; - int ret = OK; - - switch (cmd) - { - default: - { - if (_SCUIOCVALID(cmd)) - { - /* Redirect SCU commands */ - - ret = seq_ioctl(priv->seq, priv->minor, cmd, arg); - } - else - { - snerr("Unrecognized cmd: %d\n", cmd); - ret = - ENOTTY; - } - } - break; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: bh1790glc_init - * - * Description: - * Initialize the BH1790GLC device - * - * Input Parameters: - * i2c - An instance of the I2C interface to use to communicate with - * BH1790GLC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1790glc_init(FAR struct i2c_master_s *i2c, int port) -{ - FAR struct bh1790glc_dev_s tmp; - FAR struct bh1790glc_dev_s *priv = &tmp; - int ret; - - /* Setup temporary device structure for initialization */ - - priv->i2c = i2c; - priv->addr = BH1790GLC_ADDR; - priv->port = port; - - /* Check Device ID */ - - ret = bh1790glc_checkid(priv); - if (ret < 0) - { - snerr("Failed to register driver: %d\n", ret); - return ret; - } - - return OK; -} - -/**************************************************************************** - * Name: bh1790glc_register - * - * Description: - * Register the BH1790GLC character device as 'devpath' - * - * Input Parameters: - * devpath - The full path to the driver to register. E.g., "/dev/hrate0" - * minor - minor device number - * i2c - An instance of the I2C interface to use to communicate with - * BH1790GLC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1790glc_register(FAR const char *devpath, int minor, - FAR struct i2c_master_s *i2c, int port) -{ - FAR struct bh1790glc_dev_s *priv; - char path[16]; - int ret; - - /* Initialize the BH1790GLC device structure */ - - priv = (FAR struct bh1790glc_dev_s *) - kmm_malloc(sizeof(struct bh1790glc_dev_s)); - if (!priv) - { - snerr("Failed to allocate instance\n"); - return -ENOMEM; - } - - priv->i2c = i2c; - priv->addr = BH1790GLC_ADDR; - priv->port = port; - priv->seq = NULL; - priv->minor = minor; - - /* Register the character driver */ - - (void) snprintf(path, sizeof(path), "%s%d", devpath, minor); - ret = register_driver(path, &g_bh1790glcfops, 0666, priv); - if (ret < 0) - { - snerr("Failed to register driver: %d\n", ret); - kmm_free(priv); - } - - sninfo("BH1790GLC driver loaded successfully!\n"); - - return ret; -} - -#endif /* CONFIG_I2C && CONFIG_BH1790GLC */ diff --git a/drivers/sensors/kx224.c b/drivers/sensors/kx224.c deleted file mode 100644 index 408c9a599c..0000000000 --- a/drivers/sensors/kx224.c +++ /dev/null @@ -1,530 +0,0 @@ -/**************************************************************************** - * drivers/sensors/kx224.c - * - * Copyright (C) 2016 Sony Corporation - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor Sony nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(CONFIG_I2C) && defined(CONFIG_KX224) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#ifdef CONFIG_CXD56_DECI_KX224 -# define KX224_SEQ_TYPE SEQ_TYPE_DECI -#else -# define KX224_SEQ_TYPE SEQ_TYPE_NORMAL -#endif - -#define KX224_ADDR 0x1E /* I2C Slave Address */ -#define KX224_DEVID 0x2B /* Device ID */ - -#define KX224_BYTESPERSAMPLE 6 -#define KX224_ELEMENTSIZE 2 - -/* KX224 Registers */ - -#define KX224_XOUT_L 0x06 -#define KX224_WHO_AM_I 0x0F -#define KX224_CNTL1 0x18 -#define KX224_ODCNTL 0x1B - -/* Register CNTL1 */ - -#define KX224_CNTL1_TPE (1 << 0) -#define KX224_CNTL1_WUFE (1 << 1) -#define KX224_CNTL1_TDTE (1 << 2) -#define KX224_CNTL1_GSELMASK (0x18) -#define KX224_CNTL1_GSEL_8G (0x00) -#define KX224_CNTL1_GSEL_16G (0x08) -#define KX224_CNTL1_GSEL_32G (0x10) -#define KX224_CNTL1_DRDYE (1 << 5) -#define KX224_CNTL1_RES (1 << 6) -#define KX224_CNTL1_PC1 (1 << 7) - -/* Register ODCNTL */ - -#define KX224_ODCNTL_OSA_50HZ (2) -#define KX224_ODCNTL_LPRO (1 << 6) -#define KX224_ODCNTL_IIR_BYPASS (1 << 7) - -#ifndef itemsof -# define itemsof(array) (sizeof(array)/sizeof(array[0])) -#endif - -/**************************************************************************** - * Private Type Definitions - ****************************************************************************/ -/** - * @brief Structure for kx224 device - */ - -struct kx224_dev_s -{ - FAR struct i2c_master_s *i2c; /* I2C interface */ - uint8_t addr; /* I2C address */ - int port; /* I2C port */ - - struct seq_s *seq; /* Sequencer instance */ - int fifoid; /* FIFO ID */ -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* Character driver methods */ - -static int kx224_open(FAR struct file *filep); -static int kx224_close(FAR struct file *filep); -static ssize_t kx224_read(FAR struct file *filep, FAR char *buffer, - size_t buflen); -static ssize_t kx224_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen); -static int kx224_ioctl(FAR struct file *filep, int cmd, unsigned long arg); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct file_operations g_kx224fops = -{ - kx224_open, /* open */ - kx224_close, /* close */ - kx224_read, /* read */ - kx224_write, /* write */ - 0, /* seek */ - kx224_ioctl, /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - 0, /* poll */ -#endif - 0 /* unlink */ -}; - -/* Take XYZ data. */ - -static const uint16_t g_kx224inst[] = -{ - SCU_INST_SEND(KX224_XOUT_L), - SCU_INST_RECV(KX224_BYTESPERSAMPLE) | SCU_INST_LAST, -}; - -/* Reference count */ - -static int g_refcnt = 0; - -/* Sequencer instance */ - -static struct seq_s *g_seq = NULL; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ -/**************************************************************************** - * Name: kx224_getreg8 - * - * Description: - * Read from an 8-bit KX224 register - * - ****************************************************************************/ - -static uint8_t kx224_getreg8(FAR struct kx224_dev_s *priv, uint8_t regaddr) -{ - uint8_t regval; - uint16_t inst[2]; - - /* Send register to read and get the next byte */ - - inst[0] = SCU_INST_SEND(regaddr); - inst[1] = SCU_INST_RECV(1) | SCU_INST_LAST; - - scu_i2ctransfer(priv->port, priv->addr, inst, 2, ®val, 1); - - return regval; -} - -/**************************************************************************** - * Name: kx224_putreg8 - * - * Description: - * Write to an 8-bit KX224 register - * - ****************************************************************************/ - -static void kx224_putreg8(FAR struct kx224_dev_s *priv, uint8_t regaddr, - uint8_t regval) -{ - uint16_t inst[2]; - - /* Send register address and set the value */ - - inst[0] = SCU_INST_SEND(regaddr); - inst[1] = SCU_INST_SEND(regval) | SCU_INST_LAST; - - scu_i2ctransfer(priv->port, priv->addr, inst, 2, NULL, 0); -} - -/**************************************************************************** - * Name: kx224_checkid - * - * Description: - * Read and verify the KX224 chip ID - * - ****************************************************************************/ - -static int kx224_checkid(FAR struct kx224_dev_s *priv) -{ - uint8_t devid; - - /* Read device ID */ - - devid = kx224_getreg8(priv, KX224_WHO_AM_I); - - if (devid != KX224_DEVID) - { - /* ID is not Correct */ - - snerr("Wrong Device ID! %02x\n", devid); - return -ENODEV; - } - - return OK; -} - -/**************************************************************************** - * Name: kx224_initialize - * - * Description: - * Initialize and goto stand-by mode. - * - ****************************************************************************/ - -static void kx224_initialize(FAR struct kx224_dev_s *priv) -{ - uint8_t val; - - /* CNTL1 */ - - val = KX224_CNTL1_RES | KX224_CNTL1_GSEL_8G; - kx224_putreg8(priv, KX224_CNTL1, val); - - /* ODCNTL */ - - val = KX224_ODCNTL_OSA_50HZ; - kx224_putreg8(priv, KX224_ODCNTL, val); -} - -static int kx224_seqinit(FAR struct kx224_dev_s *priv) -{ - DEBUGASSERT(g_seq == NULL); - - /* Open sequencer */ - - g_seq = seq_open(KX224_SEQ_TYPE, SCU_BUS_I2C0); - if (!g_seq) - { - return -ENOENT; - } - priv->seq = g_seq; - - seq_setaddress(priv->seq, priv->addr); - - /* Set instruction and sample data information to sequencer */ - - seq_setinstruction(priv->seq, g_kx224inst, itemsof(g_kx224inst)); - seq_setsample(priv->seq, KX224_BYTESPERSAMPLE, 0, KX224_ELEMENTSIZE, false); - - return OK; -} - -/**************************************************************************** - * Name: kx224_open - * - * Description: - * This function is called whenever the KX224 device is opened. - * - ****************************************************************************/ - -static int kx224_open(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct kx224_dev_s *priv = inode->i_private; - uint8_t val; - - if (g_refcnt == 0) - { - int ret; - - ret = kx224_seqinit(priv); - if (ret < 0) - { - return ret; - } - - /* goto operating mode */ - - val = kx224_getreg8(priv, KX224_CNTL1); - val |= KX224_CNTL1_PC1; - kx224_putreg8(priv, KX224_CNTL1, val); - up_mdelay(1); - } - else - { - /* Set existing sequencer */ - - priv->seq = g_seq; - } - - g_refcnt++; - - return OK; -} - -/**************************************************************************** - * Name: kx224_close - * - * Description: - * This routine is called when the KX224 device is closed. - * - ****************************************************************************/ - -static int kx224_close(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct kx224_dev_s *priv = inode->i_private; - uint8_t val; - - g_refcnt--; - - (void) seq_ioctl(priv->seq, priv->fifoid, SCUIOC_STOP, 0); - - if (g_refcnt == 0) - { - /* goto stand-by mode */ - - val = kx224_getreg8(priv, KX224_CNTL1); - val &= ~KX224_CNTL1_PC1; - kx224_putreg8(priv, KX224_CNTL1, val); - up_mdelay(1); - - seq_close(g_seq); - g_seq = NULL; - } - else - { - (void) seq_ioctl(priv->seq, priv->fifoid, SCUIOC_FREEFIFO, 0); - } - - return OK; -} - -/**************************************************************************** - * Name: kx224_read - ****************************************************************************/ - -static ssize_t kx224_read(FAR struct file *filep, FAR char *buffer, - size_t len) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct kx224_dev_s *priv = inode->i_private; - - len = len / KX224_BYTESPERSAMPLE * KX224_BYTESPERSAMPLE; - len = seq_read(priv->seq, priv->fifoid, buffer, len); - - return len; -} - -/**************************************************************************** - * Name: kx224_write - ****************************************************************************/ - -static ssize_t kx224_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen) -{ - return -ENOSYS; -} - -/**************************************************************************** - * Name: kx224_ioctl - ****************************************************************************/ - -static int kx224_ioctl(FAR struct file *filep, int cmd, unsigned long arg) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct kx224_dev_s *priv = inode->i_private; - int ret = OK; - - switch (cmd) - { - default: - { - if (_SCUIOCVALID(cmd)) - { - /* Redirect SCU commands */ - - ret = seq_ioctl(priv->seq, priv->fifoid, cmd, arg); - } - else - { - snerr("Unrecognized cmd: %d\n", cmd); - ret = - ENOTTY; - } - } - break; - } - - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: kx224_init - * - * Description: - * Initialize the KX224 device - * - * Input Parameters: - * i2c - An instance of the I2C interface to use to communicate with - * KX224 - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int kx224_init(FAR struct i2c_master_s *i2c, int port) -{ - FAR struct kx224_dev_s tmp; - FAR struct kx224_dev_s *priv = &tmp; - int ret; - - /* Setup temporary device structure for initialization */ - - priv->i2c = i2c; - priv->addr = KX224_ADDR; - priv->port = port; - - /* Check Device ID */ - - ret = kx224_checkid(priv); - if (ret < 0) - { - snerr("Failed to register driver: %d\n", ret); - return ret; - } - - /* Initialize KX224 */ - - kx224_initialize(priv); - - return OK; -} - -/**************************************************************************** - * Name: kx224_register - * - * Description: - * Register the KX224 character device as 'devpath' - * - * Input Parameters: - * devpath - The full path to the driver to register. E.g., "/dev/accel0" - * fifoid - FIFO ID - * i2c - An instance of the I2C interface to use to communicate with - * KX224 - * port - I2C port (0 or 1) - * seq - Sequencer instance - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int kx224_register(FAR const char *devpath, int minor, - FAR struct i2c_master_s *i2c, int port) -{ - FAR struct kx224_dev_s *priv; - char path[16]; - int ret; - - /* Initialize the KX224 device structure */ - - priv = (FAR struct kx224_dev_s *)kmm_malloc(sizeof(struct kx224_dev_s)); - if (!priv) - { - snerr("Failed to allocate instance\n"); - return -ENOMEM; - } - - priv->i2c = i2c; - priv->addr = KX224_ADDR; - priv->port = port; - priv->seq = NULL; - priv->fifoid = minor; - - /* Register the character driver */ - - (void) snprintf(path, sizeof(path), "%s%d", devpath, minor); - ret = register_driver(path, &g_kx224fops, 0666, priv); - if (ret < 0) - { - snerr("Failed to register driver: %d\n", ret); - kmm_free(priv); - } - - sninfo("KX224 driver loaded successfully!\n"); - - return ret; -} - -#endif /* CONFIG_I2C && CONFIG_KX224 */ diff --git a/include/nuttx/sensors/bh1749nuc.h b/include/nuttx/sensors/bh1749nuc.h deleted file mode 100644 index c952191fe0..0000000000 --- a/include/nuttx/sensors/bh1749nuc.h +++ /dev/null @@ -1,116 +0,0 @@ -/**************************************************************************** - * bsp/include/nuttx/sensors/bh1749nuc.h - * - * Copyright (C) 2016 Sony Corporation. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor Sony nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_SENSORS_BH1749NUC_H -#define __INCLUDE_NUTTX_SENSORS_BH1749NUC_H - -#include - -#if defined(CONFIG_I2C) && defined(CONFIG_SENSOR_BH1749NUC) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Configuration ************************************************************ -/* Prerequisites: - * - * CONFIG_SENSOR_BH1749NUC - * Enables support for the BH1749NUC driver - */ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -struct i2c_master_s; - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" -{ -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Name: bh1749nuc_init - * - * Description: - * Initialize BH1749NUC color sensor device - * - * Input Parameters: - * i2c - An instance of the I2C interface to use to communicate with - * BH1749NUC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1749nuc_init(FAR struct i2c_master_s *i2c, int port); - -/**************************************************************************** - * Name: bh1749nuc_register - * - * Description: - * Register the BH1749NUC character device as 'devpath' - * - * Input Parameters: - * devpath - The full path to the driver to register. E.g., "/dev/color0" - * minor - minor device number - * i2c - An instance of the I2C interface to use to communicate with - * BH1749NUC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1749nuc_register(FAR const char *devpath, int minor, - FAR struct i2c_master_s *i2c, int port); - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* CONFIG_I2C && CONFIG_SENSOR_BH1749NUC */ -#endif /* __INCLUDE_NUTTX_SENSORS_BH1749NUC_H */ diff --git a/include/nuttx/sensors/bh1790glc.h b/include/nuttx/sensors/bh1790glc.h deleted file mode 100644 index 07a5dba6d5..0000000000 --- a/include/nuttx/sensors/bh1790glc.h +++ /dev/null @@ -1,116 +0,0 @@ -/**************************************************************************** - * bsp/include/nuttx/sensors/bh1790glc.h - * - * Copyright (C) 2016 Sony Corporation. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor Sony nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_SENSORS_BH1790GLC_H -#define __INCLUDE_NUTTX_SENSORS_BH1790GLC_H - -#include - -#if defined(CONFIG_I2C) && defined(CONFIG_SENSOR_BH1790GLC) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Configuration ************************************************************ -/* Prerequisites: - * - * CONFIG_SENSOR_BH1790GLC - * Enables support for the BH1790GLC driver - */ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -struct i2c_master_s; - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" -{ -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Name: bh1790glc_init - * - * Description: - * Initialize BH1790GLC color sensor device - * - * Input Parameters: - * i2c - An instance of the I2C interface to use to communicate with - * BH1790GLC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1790glc_init(FAR struct i2c_master_s *i2c, int port); - -/**************************************************************************** - * Name: bh1790glc_register - * - * Description: - * Register the BH1790GLC character device as 'devpath' - * - * Input Parameters: - * devpath - The full path to the driver to register. E.g., "/dev/color0" - * minor - minor device number - * i2c - An instance of the I2C interface to use to communicate with - * BH1790GLC - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int bh1790glc_register(FAR const char *devpath, int minor, - FAR struct i2c_master_s *i2c, int port); - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* CONFIG_I2C && CONFIG_SENSOR_BH1790GLC */ -#endif /* __INCLUDE_NUTTX_SENSORS_BH1790GLC_H */ diff --git a/include/nuttx/sensors/kx224.h b/include/nuttx/sensors/kx224.h deleted file mode 100644 index d49b841970..0000000000 --- a/include/nuttx/sensors/kx224.h +++ /dev/null @@ -1,117 +0,0 @@ -/**************************************************************************** - * bsp/include/nuttx/sensors/kx224.h - * - * Copyright (C) 2016 Sony Corporation. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor Sony nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#ifndef __INCLUDE_NUTTX_SENSORS_KX224_H -#define __INCLUDE_NUTTX_SENSORS_KX224_H - -#include - -#if defined(CONFIG_I2C) && defined(CONFIG_SENSOR_KX224) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Configuration ************************************************************ -/* Prerequisites: - * - * CONFIG_SENSOR_KX224 - * Enables support for the KX224 driver - */ - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -struct i2c_master_s; - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" -{ -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Name: kx224_init - * - * Description: - * Initialize KX224 accelerometer device - * - * Input Parameters: - * i2c - An instance of the I2C interface to use to communicate with - * KX224 - * port - I2C port (0 or 1) - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int kx224_init(FAR struct i2c_master_s *i2c, int port); - -/**************************************************************************** - * Name: kx224_register - * - * Description: - * Register the KX224 character device as 'devpath' - * - * Input Parameters: - * devpath - The full path to the driver to register. E.g., "/dev/accel0" - * minor - minor device number - * i2c - An instance of the I2C interface to use to communicate with - * KX224 - * port - I2C port (0 or 1) - * seq - Sequencer instance - * - * Returned Value: - * Zero (OK) on success; a negated errno value on failure. - * - ****************************************************************************/ - -int kx224_register(FAR const char *devpath, int minor, - FAR struct i2c_master_s *i2c, int port); - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* CONFIG_I2C && CONFIG_SENSOR_KX224 */ -#endif /* __INCLUDE_NUTTX_SENSORS_KX224_H */