Merged in alinjerpelea/nuttx (pull request #1018)

boards: cxd56xx: add SCU sensors

* drivers: platform: add Avago APDS9930 Proximity and Ambient light Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Rohm BH1721FVC Ambient Light Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Rohm BH1745NUC Color Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Rohm BM1383GLV/BM1383AGLV Pressure Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Rohm BM1422GMV/BM1422AGMV Magnetic Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Bosch BMI160 Sensor support

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Bosch BMP280 Barometic Pressure Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Kionix KX022/KX122 Acceleration Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Murata LT1PA01 Proximity and Ambient light Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: spresense: add Rohm RPR0521RS Proximity and Ambient light Sensor

    This sensor is connected to the SCU on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: sensors: bmi160: add optional I2C address

    Add a menu option for the case when the SDO pin is pulled to VDDIO

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Alin Jerpelea 2019-08-22 12:49:05 +00:00 committed by Gregory Nutt
parent 6d42574619
commit a91d86523c
24 changed files with 8952 additions and 19 deletions

View File

@ -17,4 +17,162 @@ config SENSORS_AK09912_SCU
Enable driver for AK09911/AK09912 Compass sensor.
NOTE: This sensor is connected to the SCU unit
config SENSORS_APDS9930_SCU
bool "Avago APDS9930 Proximity and Ambient light Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for APDS9930 proximity and ambient light sensor.
if SENSORS_APDS9930_SCU
config SENSORS_APDS9930_PROXIMITY_INTERRUPT
bool "Use Proximity interrupt"
default y
---help---
Use Interrupt when the threshold is exceeded.
In this case, SCU sequencer is not used.
endif
config SENSORS_BH1721FVC_SCU
bool "Rohm BH1721FVC Ambient Light Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for the Rohm BH1721FVC light sensor.
config SENSORS_BH1745NUC_SCU
bool "Rohm BH1745NUC Color Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for BH1745NUC color sensor.
config SENSORS_BM1383GLV_SCU
bool "Rohm BM1383GLV/BM1383AGLV Pressure Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for BM1383GLV/BM1383AGLV pressure sensor.
config SENSORS_BM1422GMV_SCU
bool "Rohm BM1422GMV/BM1422AGMV Magnetic Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for BM1422GMV/BM1422AGMV magnetic sensor.
if SENSORS_BM1422GMV_SCU
choice
prompt "Slave Address"
default BM1422GMV_SLAVE_ADDRESS_0F
config BM1422GMV_SLAVE_ADDRESS_0E
bool "0x0E"
config BM1422GMV_SLAVE_ADDRESS_0F
bool "0x0F"
endchoice
endif # SENSORS_BM1422GMV_SCU
config SENSORS_BMI160_SCU
bool "Bosch BMI160 Sensor support"
default n
select CXD56_SCU
---help---
Enable driver support for the Bosch BMI160 sensor.
if SENSORS_BMI160_SCU
choice
prompt "BMI160 Interface"
default SENSORS_BMI160_SCU_SPI
config SENSORS_BMI160_SCU_SPI
bool "BMI160 SPI Interface"
select CXD56_SPI
---help---
Enables support for the SPI interface.
config SENSORS_BMI160_SCU_I2C
bool "BMI160 I2C Interface"
select CXD56_I2C
---help---
Enables support for the I2C interface
endchoice
endif # CONFIG_SENSORS_BMI160_SCU
config SENSORS_BMP280_SCU
bool "Bosch BMP280 Barometic Pressure Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for the Bosch BMP280 barometic pressure sensor.
config SENSORS_KX022_SCU
bool "Kionix KX022/KX122 Acceleration Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for the Kionix KX022/KX122 acceleration sensor.
if SENSORS_KX022_SCU
config SENSORS_KX122
bool "KX122 register compatibility"
default n
---help---
Use KX122 which has the register upper compatibility with KX022.
endif # SENSORS_KX022
config SENSORS_LT1PA01_SCU
bool "Murata LT1PA01 Proximity and Ambient light Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for LT1PA01 proximity and ambient light sensor.
if SENSORS_LT1PA01_SCU
config LT1PA01_PROXIMITY_INTERRUPT
bool "Use Proximity interrupt"
default y
---help---
Use Interrupt when the threshold is exceeded.
In this case, SCU sequencer is not used.
endif # SENSORS_LT1PA01_SCU
config SENSORS_RPR0521RS_SCU
bool "Rohm RPR0521RS Proximity and Ambient light Sensor"
default n
select CXD56_I2C
select CXD56_SCU
---help---
Enable driver for RPR0521RS proximity and ambient light sensor.
if SENSORS_RPR0521RS_SCU
config RPR0521RS_PROXIMITY_INTERRUPT
bool "Use Proximity interrupt"
default y
---help---
Use Interrupt when the threshold is exceeded.
In this case, SCU sequencer is not used.
endif # SENSORS_RPR0521RS_SCU
endif # SCU_SENSORS

View File

@ -34,7 +34,47 @@
############################################################################
ifeq ($(CONFIG_SENSORS_AK09912_SCU),y)
CSRCS += ak09912_scu.c
CSRCS += ak09912_scu.c
endif
ifeq ($(CONFIG_SENSORS_APDS9930_SCU),y)
CSRCS += apds9930_scu.c
endif
ifeq ($(CONFIG_SENSORS_BH1721FVC_SCU),y)
CSRCS += bh1721fvc_scu.c
endif
ifeq ($(CONFIG_SENSORS_BH1745NUC_SCU),y)
CSRCS += bh1745nuc_scu.c
endif
ifeq ($(CONFIG_SENSORS_BM1383GLV_SCU),y)
CSRCS += bm1383glv_scu.c
endif
ifeq ($(CONFIG_SENSORS_BM1422GMV_SCU),y)
CSRCS += bm1422gmv_scu.c
endif
ifeq ($(CONFIG_SENSORS_BMI160_SCU),y)
CSRCS += bmi160_scu.c
endif
ifeq ($(CONFIG_SENSORS_BMP280_SCU),y)
CSRCS += bmp280_scu.c
endif
ifeq ($(CONFIG_SENSORS_KX022_SCU),y)
CSRCS += kx022_scu.c
endif
ifeq ($(CONFIG_SENSORS_LT1PA01_SCU),y)
CSRCS += lt1pa01_scu.c
endif
ifeq ($(CONFIG_SENSORS_RPR0521RS_SCU),y)
CSRCS += rpr0521rs_scu.c
endif
DEPPATH += --dep-path platform$(DELIM)sensors

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,394 @@
/****************************************************************************
* drivers/platform/sensors/bh1721fvc_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/bh1721fvc.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BH1721FVC_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define BH1721FVC_ADDR 0x23 /* I2C Slave Address */
#define BH1721FVC_BYTESPERSAMPLE 2
#define BH1721FVC_ELEMENTSIZE 0
/* BH1721FVC Opecode */
#define BH1721FVC_POWERDOWN 0x00
#define BH1721FVC_POWERON 0x01
#define BH1721FVC_AUTORESOLUTION 0x10
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/**
* @brief Structure for bh1721fvc device
*/
struct bh1721fvc_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 bh1721fvc_open(FAR struct file *filep);
static int bh1721fvc_close(FAR struct file *filep);
static ssize_t bh1721fvc_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t bh1721fvc_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int bh1721fvc_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_bh1721fvcfops =
{
bh1721fvc_open, /* open */
bh1721fvc_close, /* close */
bh1721fvc_read, /* read */
bh1721fvc_write, /* write */
0, /* seek */
bh1721fvc_ioctl, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Take ambient light data. */
static const uint16_t g_bh1721fvcinst[] =
{
SCU_INST_RECV(BH1721FVC_BYTESPERSAMPLE) | SCU_INST_LAST,
};
/* Reference count */
static int g_refcnt = 0;
/* Sequencer instance */
static struct seq_s *g_seq = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: bh1721fvc_writeopecode
*
* Description:
* Write to BH1721FVC opecode
*
****************************************************************************/
static void bh1721fvc_writeopecode(FAR struct bh1721fvc_dev_s *priv,
uint8_t opecode)
{
uint16_t inst = SCU_INST_SEND(opecode) | SCU_INST_LAST;
/* Send opecode */
scu_i2ctransfer(priv->port, priv->addr, &inst, 1, NULL, 0);
}
/****************************************************************************
* Name: bh1721fvc_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int bh1721fvc_seqinit(FAR struct bh1721fvc_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_bh1721fvcinst, itemsof(g_bh1721fvcinst));
seq_setsample(priv->seq, BH1721FVC_BYTESPERSAMPLE, 0, BH1721FVC_ELEMENTSIZE,
false);
return OK;
}
/****************************************************************************
* Name: bh1721fvc_open
*
* Description:
* This function is called whenever the BH1721FVC device is opened.
*
****************************************************************************/
static int bh1721fvc_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1721fvc_dev_s *priv = inode->i_private;
if (g_refcnt == 0)
{
int ret;
ret = bh1721fvc_seqinit(priv);
if (ret < 0)
{
return ret;
}
bh1721fvc_writeopecode(priv, BH1721FVC_POWERON);
bh1721fvc_writeopecode(priv, BH1721FVC_AUTORESOLUTION);
}
g_refcnt++;
return OK;
}
/****************************************************************************
* Name: bh1721fvc_close
*
* Description:
* This routine is called when the BH1721FVC device is closed.
*
****************************************************************************/
static int bh1721fvc_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1721fvc_dev_s *priv = inode->i_private;
g_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_refcnt == 0)
{
bh1721fvc_writeopecode(priv, BH1721FVC_POWERDOWN);
seq_close(g_seq);
g_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
return OK;
}
/****************************************************************************
* Name: bh1721fvc_read
****************************************************************************/
static ssize_t bh1721fvc_read(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1721fvc_dev_s *priv = inode->i_private;
len = len / BH1721FVC_BYTESPERSAMPLE * BH1721FVC_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->minor, buffer, len);
return len;
}
/****************************************************************************
* Name: bh1721fvc_write
****************************************************************************/
static ssize_t bh1721fvc_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: bh1721fvc_ioctl
****************************************************************************/
static int bh1721fvc_ioctl(FAR struct file *filep, int cmd,
unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1721fvc_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: bh1721fvc_init
*
* Description:
* Initialize the BH1721FVC device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BH1721FVC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1721fvc_init(FAR struct i2c_master_s *i2c, int port)
{
return OK;
}
/****************************************************************************
* Name: bh1721fvc_register
*
* Description:
* Register the BH1721FVC ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* BH1721FVC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1721fvc_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct bh1721fvc_dev_s *priv;
char path[16];
int ret;
/* Initialize the BH1721FVC device structure */
priv = (FAR struct bh1721fvc_dev_s *)
kmm_malloc(sizeof(struct bh1721fvc_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = BH1721FVC_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_bh1721fvcfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_BH1721FVC_SCU */

View File

@ -0,0 +1,533 @@
/****************************************************************************
* drivers/platform/sensors/bh1745nuc_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/bh1745nuc.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BH1745NUC_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define BH1745NUC_ADDR 0x39 /* I2C Slave Address */
#define BH1745NUC_MANUFACTID 0xE0 /* Manufact ID */
#define BH1745NUC_PARTID 0x0B /* Part ID */
#define BH1745NUC_BYTESPERSAMPLE 8
#define BH1745NUC_ELEMENTSIZE 0
/* BH1745NUC Registers */
#define BH1745NUC_SYSTEM_CONTROL 0x40
#define BH1745NUC_MODE_CONTROL1 0x41
#define BH1745NUC_MODE_CONTROL2 0x42
#define BH1745NUC_MODE_CONTROL3 0x44
#define BH1745NUC_RED_DATA_LSB 0x50
#define BH1745NUC_MANUFACTURER_ID 0x92
/* Register SYSTEM_CONTROL */
#define BH1745NUC_SYSTEM_CONTROL_SW_RESET (1 << 7)
#define BH1745NUC_SYSTEM_CONTROL_INT_RESET (1 << 6)
/* Register MODE_CONTROL1 */
#define BH1745NUC_MODE_CONTROL1_MEAS_TIME160MS (0x00)
/* Register MODE_CONTROL2 */
#define BH1745NUC_MODE_CONTROL2_ADC_GAIN_X1 (0)
#define BH1745NUC_MODE_CONTROL2_ADC_GAIN_X2 (1)
#define BH1745NUC_MODE_CONTROL2_ADC_GAIN_X16 (2)
#define BH1745NUC_MODE_CONTROL2_RGBC_EN (1 << 4)
/* Register MODE_CONTROL3 */
#define BH1745NUC_MODE_CONTROL3_VAL (0x02)
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/* Structure for bh1745nuc device */
struct bh1745nuc_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 bh1745nuc_open(FAR struct file *filep);
static int bh1745nuc_close(FAR struct file *filep);
static ssize_t bh1745nuc_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t bh1745nuc_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int bh1745nuc_ioctl(FAR struct file *filep, int cmd,
unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_bh1745nucfops =
{
bh1745nuc_open, /* open */
bh1745nuc_close, /* close */
bh1745nuc_read, /* read */
bh1745nuc_write, /* write */
0, /* seek */
bh1745nuc_ioctl, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Take color data. */
static const uint16_t g_bh1745nucinst[] =
{
SCU_INST_SEND(BH1745NUC_RED_DATA_LSB),
SCU_INST_RECV(BH1745NUC_BYTESPERSAMPLE) | SCU_INST_LAST,
};
/* Reference count */
static int g_refcnt = 0;
/* Sequencer instance */
static struct seq_s *g_seq = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: bh1745nuc_getreg8
*
* Description:
* Read from an 8-bit BH1745NUC register
*
****************************************************************************/
static uint8_t bh1745nuc_getreg8(FAR struct bh1745nuc_dev_s *priv,
uint8_t regaddr)
{
uint8_t regval = 0;
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, &regval, 1);
return regval;
}
/****************************************************************************
* Name: bh1745nuc_putreg8
*
* Description:
* Write to an 8-bit BH1745NUC register
*
****************************************************************************/
static void bh1745nuc_putreg8(FAR struct bh1745nuc_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: bh1745nuc_checkid
*
* Description:
* Read and verify the BH1745NUC chip ID
*
****************************************************************************/
static int bh1745nuc_checkid(FAR struct bh1745nuc_dev_s *priv)
{
uint8_t id;
/* Read Manufact ID */
id = bh1745nuc_getreg8(priv, BH1745NUC_MANUFACTURER_ID);
if (id != BH1745NUC_MANUFACTID)
{
/* Manufact ID is not Correct */
snerr("Wrong Manufact ID! %02x\n", id);
return -ENODEV;
}
/* Read Part ID */
id = bh1745nuc_getreg8(priv, BH1745NUC_SYSTEM_CONTROL);
if ((id & 0x3f) != BH1745NUC_PARTID)
{
/* Part ID is not Correct */
snerr("Wrong Part ID! %02x\n", id);
return -ENODEV;
}
return OK;
}
/****************************************************************************
* Name: bh1745nuc_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int bh1745nuc_seqinit(FAR struct bh1745nuc_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_bh1745nucinst, itemsof(g_bh1745nucinst));
seq_setsample(priv->seq, BH1745NUC_BYTESPERSAMPLE, 0, BH1745NUC_ELEMENTSIZE,
false);
return OK;
}
/****************************************************************************
* Name: bh1745nuc_open
*
* Description:
* This function is called whenever the BH1745NUC device is opened.
*
****************************************************************************/
static int bh1745nuc_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1745nuc_dev_s *priv = inode->i_private;
uint8_t val;
if (g_refcnt == 0)
{
int ret;
ret = bh1745nuc_seqinit(priv);
if (ret < 0)
{
return ret;
}
/* MODE_CONTROL1 */
val = BH1745NUC_MODE_CONTROL1_MEAS_TIME160MS;
bh1745nuc_putreg8(priv, BH1745NUC_MODE_CONTROL1, val);
/* MODE_CONTROL2 */
val = BH1745NUC_MODE_CONTROL2_RGBC_EN |
BH1745NUC_MODE_CONTROL2_ADC_GAIN_X16;
bh1745nuc_putreg8(priv, BH1745NUC_MODE_CONTROL2, val);
/* MODE_CONTROL3 */
val = BH1745NUC_MODE_CONTROL3_VAL;
bh1745nuc_putreg8(priv, BH1745NUC_MODE_CONTROL3, val);
}
else
{
/* Set existing sequencer */
priv->seq = g_seq;
}
g_refcnt++;
return OK;
}
/****************************************************************************
* Name: bh1745nuc_close
*
* Description:
* This routine is called when the BH1745NUC device is closed.
*
****************************************************************************/
static int bh1745nuc_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1745nuc_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 = BH1745NUC_SYSTEM_CONTROL_SW_RESET |
BH1745NUC_SYSTEM_CONTROL_INT_RESET;
bh1745nuc_putreg8(priv, BH1745NUC_SYSTEM_CONTROL, val);
seq_close(g_seq);
g_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
return OK;
}
/****************************************************************************
* Name: bh1745nuc_read
****************************************************************************/
static ssize_t bh1745nuc_read(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1745nuc_dev_s *priv = inode->i_private;
len = len / BH1745NUC_BYTESPERSAMPLE * BH1745NUC_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->minor, buffer, len);
return len;
}
/****************************************************************************
* Name: bh1745nuc_write
****************************************************************************/
static ssize_t bh1745nuc_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: bh1745nuc_ioctl
****************************************************************************/
static int bh1745nuc_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bh1745nuc_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: bh1745nuc_init
*
* Description:
* Initialize the BH1745NUC device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BH1745NUC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1745nuc_init(FAR struct i2c_master_s *i2c, int port)
{
FAR struct bh1745nuc_dev_s tmp;
FAR struct bh1745nuc_dev_s *priv = &tmp;
int ret;
/* Setup temporary device structure for initialization */
priv->i2c = i2c;
priv->addr = BH1745NUC_ADDR;
priv->port = port;
/* Check Device ID */
ret = bh1745nuc_checkid(priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bh1745nuc_register
*
* Description:
* Register the BH1745NUC 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
* BH1745NUC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1745nuc_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct bh1745nuc_dev_s *priv;
char path[16];
int ret;
/* Initialize the BH1745NUC device structure */
priv = (FAR struct bh1745nuc_dev_s *)
kmm_malloc(sizeof(struct bh1745nuc_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = BH1745NUC_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_bh1745nucfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
sninfo("BH1745NUC driver loaded successfully!\n");
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_BH1745NUC_SCU */

View File

@ -0,0 +1,568 @@
/****************************************************************************
* drivers/platform/sensors/bm1383glv_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/bm1383glv.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BM1383GLV_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define BM1383GLV_ADDR 0x5D /* I2C Slave Address */
#define BM1383GLV_DEVID 0x31
#define BM1383AGLV_DEVID 0x32
/* Device ID */
#define BM1383GLV_BYTESPERSAMPLE 3
#define BM1383GLV_ELEMENTSIZE 0
/* BM1383GLV Registers */
#define BM1383GLV_ID 0x10
#define BM1383GLV_POWER_DOWN 0x12
#define BM1383GLV_RESET 0x13
#define BM1383GLV_MODE_CONTROL 0x14
#define BM1383GLV_PRESSURE_MSB 0x1C
#define BM1383AGLV_PRESSURE_MSB 0x1A
/* Register POWER_DOWN */
#define BM1383GLV_POWER_DOWN_PWR_DOWN (1 << 0)
/* Register RESET */
#define BM1383GLV_RESET_RSTB (1 << 0)
/* Register MODE_CONTROL */
#define BM1383GLV_MODE_CONTROL_AVE_NUM64 (6 << 5)
#define BM1383GLV_MODE_CONTROL_T_AVE (1 << 3)
#define BM1383GLV_MODE_CONTORL_MODE_200MS (4 << 0)
#define BM1383AGLV_MODE_CONTROL_AVE_NUM64 (6 << 5)
#define BM1383AGLV_MODE_CONTROL_RESERVED (1 << 3)
#define BM1383AGLV_MODE_CONTROL_CONTINUOUS (2 << 0)
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/* Structure for bm1383glv device */
struct bm1383glv_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 bm1383glv_open(FAR struct file *filep);
static int bm1383glv_close(FAR struct file *filep);
static ssize_t bm1383glv_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t bm1383glv_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int bm1383glv_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_bm1383glvfops =
{
bm1383glv_open, /* open */
bm1383glv_close, /* close */
bm1383glv_read, /* read */
bm1383glv_write, /* write */
0, /* seek */
bm1383glv_ioctl, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Device is not BM1383AGLV but BM1383GLV */
static uint8_t g_is_bm1383glv = 0;
/* Take press data for BM1383GLV */
static const uint16_t g_bm1383glvinst[] =
{
SCU_INST_SEND(BM1383GLV_PRESSURE_MSB),
SCU_INST_RECV(BM1383GLV_BYTESPERSAMPLE) | SCU_INST_LAST,
};
/* Take press data for BM1383AGLV */
static const uint16_t g_bm1383aglvinst[] =
{
SCU_INST_SEND(BM1383AGLV_PRESSURE_MSB),
SCU_INST_RECV(BM1383GLV_BYTESPERSAMPLE) | SCU_INST_LAST,
};
/* Reference count */
static int g_refcnt = 0;
/* Sequencer instance */
static struct seq_s *g_seq = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: bm1383glv_getreg8
*
* Description:
* Read from an 8-bit BM1383GLV register
*
****************************************************************************/
static uint8_t bm1383glv_getreg8(FAR struct bm1383glv_dev_s *priv,
uint8_t regaddr)
{
uint8_t regval = 0;
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, &regval, 1);
return regval;
}
/****************************************************************************
* Name: bm1383glv_putreg8
*
* Description:
* Write to an 8-bit BM1383GLV register
*
****************************************************************************/
static void bm1383glv_putreg8(FAR struct bm1383glv_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: bm1383glv_checkid
*
* Description:
* Read and verify the BM1383GLV chip ID
*
****************************************************************************/
static int bm1383glv_checkid(FAR struct bm1383glv_dev_s *priv)
{
uint8_t devid;
/* Read device ID */
devid = bm1383glv_getreg8(priv, BM1383GLV_ID);
if ((devid != BM1383GLV_DEVID) && (devid != BM1383AGLV_DEVID))
{
/* ID is not Correct */
snerr("Wrong Device ID! %02x\n", devid);
return -ENODEV;
}
if (devid == BM1383GLV_DEVID)
{
/* Device is BM1383GLV, which remains for backward compatibility */
g_is_bm1383glv = 1;
}
return OK;
}
/****************************************************************************
* Name: bm1383glv_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int bm1383glv_seqinit(FAR struct bm1383glv_dev_s *priv)
{
const uint16_t *inst;
uint16_t nr;
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 */
if (g_is_bm1383glv)
{
inst = g_bm1383glvinst;
nr = itemsof(g_bm1383glvinst);
}
else
{
inst = g_bm1383aglvinst;
nr = itemsof(g_bm1383aglvinst);
}
seq_setinstruction(priv->seq, inst, nr);
seq_setsample(priv->seq, BM1383GLV_BYTESPERSAMPLE, 0, BM1383GLV_ELEMENTSIZE,
false);
return OK;
}
/****************************************************************************
* Name: bm1383glv_open
*
* Description:
* This function is called whenever the BM1383GLV device is opened.
*
****************************************************************************/
static int bm1383glv_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1383glv_dev_s *priv = inode->i_private;
uint8_t val;
if (g_refcnt == 0)
{
int ret;
ret = bm1383glv_seqinit(priv);
if (ret < 0)
{
return ret;
}
/* goto reset mode */
bm1383glv_putreg8(priv, BM1383GLV_POWER_DOWN, BM1383GLV_POWER_DOWN_PWR_DOWN);
up_mdelay(1);
/* goto stand-by mode */
bm1383glv_putreg8(priv, BM1383GLV_RESET, BM1383GLV_RESET_RSTB);
/* start sampling */
if (g_is_bm1383glv)
{
val = BM1383GLV_MODE_CONTROL_AVE_NUM64 |
BM1383GLV_MODE_CONTROL_T_AVE |
BM1383GLV_MODE_CONTORL_MODE_200MS;
}
else
{
val = BM1383AGLV_MODE_CONTROL_AVE_NUM64 |
BM1383AGLV_MODE_CONTROL_RESERVED |
BM1383AGLV_MODE_CONTROL_CONTINUOUS;
}
bm1383glv_putreg8(priv, BM1383GLV_MODE_CONTROL, val);
}
else
{
/* Set existing sequencer */
priv->seq = g_seq;
}
g_refcnt++;
return OK;
}
/****************************************************************************
* Name: bm1383glv_close
*
* Description:
* This routine is called when the BM1383GLV device is closed.
*
****************************************************************************/
static int bm1383glv_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1383glv_dev_s *priv = inode->i_private;
g_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_refcnt == 0)
{
/* goto stand-by mode */
bm1383glv_putreg8(priv, BM1383GLV_MODE_CONTROL, 0);
/* goto reset mode */
bm1383glv_putreg8(priv, BM1383GLV_RESET, 0);
/* goto power-down mode */
bm1383glv_putreg8(priv, BM1383GLV_POWER_DOWN, 0);
seq_close(g_seq);
g_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
return OK;
}
/****************************************************************************
* Name: bm1383glv_read
****************************************************************************/
static ssize_t bm1383glv_read(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1383glv_dev_s *priv = inode->i_private;
len = len / BM1383GLV_BYTESPERSAMPLE * BM1383GLV_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->minor, buffer, len);
return len;
}
/****************************************************************************
* Name: bm1383glv_write
****************************************************************************/
static ssize_t bm1383glv_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: bm1383glv_ioctl
****************************************************************************/
static int bm1383glv_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1383glv_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: bm1383glv_init
*
* Description:
* Initialize the BM1383GLV device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BM1383GLV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1383glv_init(FAR struct i2c_master_s *i2c, int port)
{
FAR struct bm1383glv_dev_s tmp;
FAR struct bm1383glv_dev_s *priv = &tmp;
int ret;
/* Setup temporary device structure for initialization */
priv->i2c = i2c;
priv->addr = BM1383GLV_ADDR;
priv->port = port;
/* Check Device ID */
ret = bm1383glv_checkid(priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bm1383glv_register
*
* Description:
* Register the BM1383GLV character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/press0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* BM1383GLV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1383glv_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct bm1383glv_dev_s *priv;
char path[16];
int ret;
/* Initialize the BM1383GLV device structure */
priv = (FAR struct bm1383glv_dev_s *)
kmm_malloc(sizeof(struct bm1383glv_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = BM1383GLV_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_bm1383glvfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
sninfo("BM1383GLV driver loaded successfully!\n");
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_BM1383GLV_SCU */

View File

@ -0,0 +1,555 @@
/****************************************************************************
* drivers/platform/sensors/bm1422gmv_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/bm1422gmv.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BM1422GMV_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_CXD56_DECI_BM1422GMV
# define BM1422GMV_SEQ_TYPE SEQ_TYPE_DECI
#else
# define BM1422GMV_SEQ_TYPE SEQ_TYPE_NORMAL
#endif
/* I2C Slave Address */
#ifdef CONFIG_BM1422GMV_SLAVE_ADDRESS_0F
#define BM1422GMV_ADDR 0x0F
#else
#define BM1422GMV_ADDR 0x0E
#endif
#define BM1422GMV_DEVID 0x41 /* Device ID */
#define BM1422GMV_BYTESPERSAMPLE 6
#define BM1422GMV_ELEMENTSIZE 2
/* BM1422GMV Registers */
#define BM1422GMV_WIA 0x0F
#define BM1422GMV_DATAX 0x10
#define BM1422GMV_CNTL1 0x1B
#define BM1422GMV_CNTL2 0x1C
#define BM1422GMV_CNTL3 0x1D
#define BM1422GMV_CNTL4 0x5C
/* Register CNTL1 */
#define BM1422GMV_CNTL1_PC1 (1 << 7)
#define BM1422GMV_CNTL1_OUT_BIT (1 << 6)
#define BM1422GMV_CNTL1_RST_LV (1 << 5)
#define BM1422GMV_CNTL1_ODR_10Hz (0 << 3)
#define BM1422GMV_CNTL1_ODR_20Hz (2 << 3)
#define BM1422GMV_CNTL1_ODR_100Hz (1 << 3)
#define BM1422GMV_CNTL1_ODR_1000Hz (3 << 3)
#define BM1422GMV_CNTL1_FS1 (1 << 1)
/* Register CNTL2 */
#define BM1422GMV_CNTL2_DREN (1 << 3)
#define BM1422GMV_CNTL2_DRP (1 << 2)
/* Register CNTL3 */
#define BM1422GMV_CNTL3_FORCE (1 << 6)
/* Register CNTL4 */
#define BM1422GMV_CNTL4_VAL 0x0000
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/* Structure for bm1422gmv device */
struct bm1422gmv_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 bm1422gmv_open(FAR struct file *filep);
static int bm1422gmv_close(FAR struct file *filep);
static ssize_t bm1422gmv_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t bm1422gmv_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int bm1422gmv_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_bm1422gmvfops =
{
bm1422gmv_open, /* open */
bm1422gmv_close, /* close */
bm1422gmv_read, /* read */
bm1422gmv_write, /* write */
0, /* seek */
bm1422gmv_ioctl, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Take XYZ data. */
static const uint16_t g_bm1422gmvinst[] =
{
SCU_INST_SEND(BM1422GMV_DATAX),
SCU_INST_RECV(BM1422GMV_BYTESPERSAMPLE) | SCU_INST_LAST,
};
/* Reference count */
static int g_refcnt = 0;
/* Sequencer instance */
static struct seq_s *g_seq = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: bm1422gmv_getreg8
*
* Description:
* Read from an 8-bit BM1422GMV register
*
****************************************************************************/
static uint8_t bm1422gmv_getreg8(FAR struct bm1422gmv_dev_s *priv,
uint8_t regaddr)
{
uint8_t regval = 0;
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, &regval, 1);
return regval;
}
/****************************************************************************
* Name: bm1422gmv_putreg8
*
* Description:
* Write to an 8-bit BM1422GMV register
*
****************************************************************************/
static void bm1422gmv_putreg8(FAR struct bm1422gmv_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: bm1422gmv_putreg16
*
* Description:
* Write to an 16-bit BM1422GMV register
*
****************************************************************************/
static void bm1422gmv_putreg16(FAR struct bm1422gmv_dev_s *priv,
uint8_t regaddr, uint16_t regval)
{
uint16_t inst[3];
/* Send register address and set the value */
inst[0] = SCU_INST_SEND(regaddr);
inst[1] = SCU_INST_SEND((uint8_t)(regval & 0xff));
inst[2] = SCU_INST_SEND((uint8_t)(regval >> 8)) | SCU_INST_LAST;
scu_i2ctransfer(priv->port, priv->addr, inst, 3, NULL, 0);
}
/****************************************************************************
* Name: bm1422gmv_checkid
*
* Description:
* Read and verify the BM1422GMV chip ID
*
****************************************************************************/
static int bm1422gmv_checkid(FAR struct bm1422gmv_dev_s *priv)
{
uint8_t devid;
/* Read device ID */
devid = bm1422gmv_getreg8(priv, BM1422GMV_WIA);
if (devid != BM1422GMV_DEVID)
{
/* ID is not Correct */
snerr("Wrong Device ID! %02x\n", devid);
return -ENODEV;
}
return OK;
}
/****************************************************************************
* Name: bm1422gmv_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int bm1422gmv_seqinit(FAR struct bm1422gmv_dev_s *priv)
{
DEBUGASSERT(g_seq == NULL);
/* Open sequencer */
g_seq = seq_open(BM1422GMV_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_bm1422gmvinst, itemsof(g_bm1422gmvinst));
seq_setsample(priv->seq, BM1422GMV_BYTESPERSAMPLE, 0, BM1422GMV_ELEMENTSIZE,
false);
return OK;
}
/****************************************************************************
* Name: bm1422gmv_open
*
* Description:
* This function is called whenever the BM1422GMV device is opened.
*
****************************************************************************/
static int bm1422gmv_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1422gmv_dev_s *priv = inode->i_private;
uint8_t val;
if (g_refcnt == 0)
{
int ret;
ret = bm1422gmv_seqinit(priv);
if (ret < 0)
{
return ret;
}
/* goto active mode */
val = BM1422GMV_CNTL1_PC1 | BM1422GMV_CNTL1_OUT_BIT |
BM1422GMV_CNTL1_ODR_100Hz;
bm1422gmv_putreg8(priv, BM1422GMV_CNTL1, val);
up_mdelay(1);
/* release reset */
bm1422gmv_putreg16(priv, BM1422GMV_CNTL4, BM1422GMV_CNTL4_VAL);
/* start sampling */
bm1422gmv_putreg8(priv, BM1422GMV_CNTL3, BM1422GMV_CNTL3_FORCE);
}
else
{
/* Set existing sequencer */
priv->seq = g_seq;
}
g_refcnt++;
return OK;
}
/****************************************************************************
* Name: bm1422gmv_close
*
* Description:
* This routine is called when the BM1422GMV device is closed.
*
****************************************************************************/
static int bm1422gmv_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1422gmv_dev_s *priv = inode->i_private;
g_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_refcnt == 0)
{
/* goto power-down mode */
bm1422gmv_putreg8(priv, BM1422GMV_CNTL1, BM1422GMV_CNTL1_RST_LV);
up_mdelay(1);
seq_close(g_seq);
g_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
return OK;
}
/****************************************************************************
* Name: bm1422gmv_read
****************************************************************************/
static ssize_t bm1422gmv_read(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1422gmv_dev_s *priv = inode->i_private;
len = len / BM1422GMV_BYTESPERSAMPLE * BM1422GMV_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->minor, buffer, len);
return len;
}
/****************************************************************************
* Name: bm1422gmv_write
****************************************************************************/
static ssize_t bm1422gmv_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: bm1422gmv_ioctl
****************************************************************************/
static int bm1422gmv_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct bm1422gmv_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: bm1422gmv_init
*
* Description:
* Initialize the BM1422GMV device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BM1422GMV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1422gmv_init(FAR struct i2c_master_s *i2c, int port)
{
FAR struct bm1422gmv_dev_s tmp;
FAR struct bm1422gmv_dev_s *priv = &tmp;
int ret;
/* Setup temporary device structure for initialization */
priv->i2c = i2c;
priv->addr = BM1422GMV_ADDR;
priv->port = port;
/* Check Device ID */
ret = bm1422gmv_checkid(priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
return ret;
}
return OK;
}
/****************************************************************************
* Name: bm1422gmv_register
*
* Description:
* Register the BM1422GMV character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/mag0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* BM1422GMV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1422gmv_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct bm1422gmv_dev_s *priv;
char path[16];
int ret;
/* Initialize the BM1422GMV device structure */
priv = (FAR struct bm1422gmv_dev_s *)
kmm_malloc(sizeof(struct bm1422gmv_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = BM1422GMV_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_bm1422gmvfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
sninfo("BM1422GMV driver loaded successfully!\n");
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_BM1422GMV_SCU */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,536 @@
/****************************************************************************
* drivers/platform/sensors/kx022_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/kx022.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_KX022_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_CXD56_DECI_KX022
# define KX022_SEQ_TYPE SEQ_TYPE_DECI
#else
# define KX022_SEQ_TYPE SEQ_TYPE_NORMAL
#endif
#ifdef CONFIG_SENSORS_KX122
# define KX022_ADDR 0x1F /* I2C Slave Address */
# define KX022_DEVID 0x1B /* Device ID */
#else
# define KX022_ADDR 0x1E /* I2C Slave Address */
# define KX022_DEVID 0x14 /* Device ID */
#endif
#define KX022_BYTESPERSAMPLE 6
#define KX022_ELEMENTSIZE 2
/* KX022 Registers */
#define KX022_XOUT_L 0x06
#define KX022_WHO_AM_I 0x0F
#define KX022_CNTL1 0x18
#define KX022_ODCNTL 0x1B
/* Register CNTL1 */
#define KX022_CNTL1_TPE (1 << 0)
#define KX022_CNTL1_WUFE (1 << 1)
#define KX022_CNTL1_TDTE (1 << 2)
#define KX022_CNTL1_GSELMASK (0x18)
#define KX022_CNTL1_GSEL_2G (0x00)
#define KX022_CNTL1_GSEL_4G (0x08)
#define KX022_CNTL1_GSEL_8G (0x10)
#define KX022_CNTL1_DRDYE (1 << 5)
#define KX022_CNTL1_RES (1 << 6)
#define KX022_CNTL1_PC1 (1 << 7)
/* Register ODCNTL */
#define KX022_ODCNTL_OSA_50HZ (2)
#define KX022_ODCNTL_LPRO (1 << 6)
#define KX022_ODCNTL_IIR_BYPASS (1 << 7)
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/* Structure for kx022 device */
struct kx022_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 kx022_open(FAR struct file *filep);
static int kx022_close(FAR struct file *filep);
static ssize_t kx022_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t kx022_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int kx022_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_kx022fops =
{
kx022_open, /* open */
kx022_close, /* close */
kx022_read, /* read */
kx022_write, /* write */
0, /* seek */
kx022_ioctl, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Take XYZ data. */
static const uint16_t g_kx022inst[] =
{
SCU_INST_SEND(KX022_XOUT_L),
SCU_INST_RECV(KX022_BYTESPERSAMPLE) | SCU_INST_LAST,
};
/* Reference count */
static int g_refcnt = 0;
/* Sequencer instance */
static struct seq_s *g_seq = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: kx022_getreg8
*
* Description:
* Read from an 8-bit KX022 register
*
****************************************************************************/
static uint8_t kx022_getreg8(FAR struct kx022_dev_s *priv, uint8_t regaddr)
{
uint8_t regval = 0;
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, &regval, 1);
return regval;
}
/****************************************************************************
* Name: kx022_putreg8
*
* Description:
* Write to an 8-bit KX022 register
*
****************************************************************************/
static void kx022_putreg8(FAR struct kx022_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: kx022_checkid
*
* Description:
* Read and verify the KX022 chip ID
*
****************************************************************************/
static int kx022_checkid(FAR struct kx022_dev_s *priv)
{
uint8_t devid;
/* Read device ID */
devid = kx022_getreg8(priv, KX022_WHO_AM_I);
if (devid != KX022_DEVID)
{
/* ID is not Correct */
snerr("Wrong Device ID! %02x\n", devid);
return -ENODEV;
}
return OK;
}
/****************************************************************************
* Name: kx022_initialize
*
* Description:
* Initialize and goto stand-by mode.
*
****************************************************************************/
static void kx022_initialize(FAR struct kx022_dev_s *priv)
{
uint8_t val;
/* CNTL1 */
val = KX022_CNTL1_RES | KX022_CNTL1_GSEL_2G;
kx022_putreg8(priv, KX022_CNTL1, val);
/* ODCNTL */
val = KX022_ODCNTL_OSA_50HZ;
kx022_putreg8(priv, KX022_ODCNTL, val);
}
static int kx022_seqinit(FAR struct kx022_dev_s *priv)
{
DEBUGASSERT(g_seq == NULL);
/* Open sequencer */
g_seq = seq_open(KX022_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_kx022inst, itemsof(g_kx022inst));
seq_setsample(priv->seq, KX022_BYTESPERSAMPLE, 0, KX022_ELEMENTSIZE, false);
return OK;
}
/****************************************************************************
* Name: kx022_open
*
* Description:
* This function is called whenever the KX022 device is opened.
*
****************************************************************************/
static int kx022_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct kx022_dev_s *priv = inode->i_private;
uint8_t val;
if (g_refcnt == 0)
{
int ret;
ret = kx022_seqinit(priv);
if (ret < 0)
{
return ret;
}
/* goto operating mode */
val = kx022_getreg8(priv, KX022_CNTL1);
val |= KX022_CNTL1_PC1;
kx022_putreg8(priv, KX022_CNTL1, val);
up_mdelay(1);
}
else
{
/* Set existing sequencer */
priv->seq = g_seq;
}
g_refcnt++;
return OK;
}
/****************************************************************************
* Name: kx022_close
*
* Description:
* This routine is called when the KX022 device is closed.
*
****************************************************************************/
static int kx022_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct kx022_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 = kx022_getreg8(priv, KX022_CNTL1);
val &= ~KX022_CNTL1_PC1;
kx022_putreg8(priv, KX022_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: kx022_read
****************************************************************************/
static ssize_t kx022_read(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct kx022_dev_s *priv = inode->i_private;
len = len / KX022_BYTESPERSAMPLE * KX022_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->fifoid, buffer, len);
return len;
}
/****************************************************************************
* Name: kx022_write
****************************************************************************/
static ssize_t kx022_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: kx022_ioctl
****************************************************************************/
static int kx022_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct kx022_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: kx022_init
*
* Description:
* Initialize the KX022 device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* KX022
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int kx022_init(FAR struct i2c_master_s *i2c, int port)
{
FAR struct kx022_dev_s tmp;
FAR struct kx022_dev_s *priv = &tmp;
int ret;
/* Setup temporary device structure for initialization */
priv->i2c = i2c;
priv->addr = KX022_ADDR;
priv->port = port;
/* Check Device ID */
ret = kx022_checkid(priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
return ret;
}
/* Initialize KX022 */
kx022_initialize(priv);
return OK;
}
/****************************************************************************
* Name: kx022_register
*
* Description:
* Register the KX022 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
* KX022
* port - I2C port (0 or 1)
* seq - Sequencer instance
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int kx022_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct kx022_dev_s *priv;
char path[16];
int ret;
/* Initialize the KX022 device structure */
priv = (FAR struct kx022_dev_s *)kmm_malloc(sizeof(struct kx022_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = KX022_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_kx022fops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
sninfo("KX022 driver loaded successfully!\n");
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_KX022_SCU */

View File

@ -0,0 +1,893 @@
/****************************************************************************
* drivers/platform/sensors/lt1pa01_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/lt1pa01.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_LT1PA01_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define LT1PA01_ADDR 0x44 /* I2C Slave Address */
#define LT1PA01_DEVICEID 0xC8 /* Device ID */
#define LT1PA01_ALS_BYTESPERSAMPLE 2
#define LT1PA01_PROX_BYTESPERSAMPLE 1
#define LT1PA01_ELEMENTSIZE 0
/* LT1PA01 Registers */
#define LT1PA01_ID 0x00
#define LT1PA01_CONFIG0 0x01
#define LT1PA01_CONFIG1 0x02
#define LT1PA01_CONFIG2 0x03
#define LT1PA01_INTCONFIG 0x04
#define LT1PA01_PROX_INT_TL 0x05
#define LT1PA01_PROX_INT_TH 0x06
#define LT1PA01_ALS_INT_TL 0x07
#define LT1PA01_ALS_INT_TLH 0x08
#define LT1PA01_ALS_INT_TH 0x09
#define LT1PA01_PROX_DATA 0x0A
#define LT1PA01_ALS_DATA_HB 0x0B
#define LT1PA01_ALS_DATA_LB 0x0C
#define LT1PA01_PROX_AMBIR 0x0D
#define LT1PA01_CONFIG3 0x0E
/* Register ID */
#define LT1PA01_ID_MASK 0xF8
/* Register CONFIG0 */
#define LT1PA01_PROX_DIS (0 << 5)
#define LT1PA01_PROX_EN (1 << 5)
#define LT1PA01_PROX_SLP_800MS (0 << 2)
#define LT1PA01_PROX_SLP_200MS (1 << 2)
#define LT1PA01_PROX_SLP_100MS (2 << 2)
#define LT1PA01_PROX_IRDR_DRV0 (0 << 0) /* 3.6mA */
#define LT1PA01_PROX_IRDR_DRV1 (1 << 0) /* 7.2mA */
#define LT1PA01_PROX_IRDR_DRV2 (2 << 0) /* 10.8mA */
#define LT1PA01_PROX_IRDR_DRV3 (3 << 0) /* 14.4mA */
/* Register CONFIG1 */
#define LT1PA01_INT_ALG_COMPARATOR (0 << 7)
#define LT1PA01_INT_ALG_HYSTERESIS (1 << 7)
#define LT1PA01_ALS_DIS (0 << 2)
#define LT1PA01_ALS_EN (1 << 2)
#define LT1PA01_ALS_ALS_RANGE0 (0 << 0) /* 62.5 Lux */
#define LT1PA01_ALS_ALS_RANGE1 (1 << 0) /* 125 Lux */
#define LT1PA01_ALS_ALS_RANGE2 (2 << 0) /* 1000 Lux */
#define LT1PA01_ALS_ALS_RANGE3 (3 << 0) /* 2000 Lux */
#define LT1PA01_ALS_ALS_RANGE_MASK (3 << 0)
/* Register INTCONFIG */
#define LT1PA01_PORX_INT_FLG (1 << 7)
#define LT1PA01_PORX_INT_PRST1 (0 << 5)
#define LT1PA01_PORX_INT_PRST2 (1 << 5)
#define LT1PA01_PORX_INT_PRST4 (2 << 5)
#define LT1PA01_PORX_INT_PRST8 (3 << 5)
#define LT1PA01_PORX_INT_PRST_MASK (3 << 5)
#define LT1PA01_PWR_FAIL (1 << 4)
#define LT1PA01_ALS_INT_FLG (1 << 3)
#define LT1PA01_ALS_INT_PRST1 (0 << 1)
#define LT1PA01_ALS_INT_PRST2 (1 << 1)
#define LT1PA01_ALS_INT_PRST4 (2 << 1)
#define LT1PA01_ALS_INT_PRST8 (3 << 1)
#define LT1PA01_INT_CFG_ALS_AND_PROX (1 << 0)
#define LT1PA01_INT_CFG_ALS_OR_PROX (0 << 0)
/* Register INTCONFIG */
#define LT1PA01_SW_RESET 0x38
/* PROX INT threshold default value */
#define LT1PA01_PROX_INT_TL_DEFAULT 0x03
#define LT1PA01_PROX_INT_TH_DEFAULT 0x03
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/**
* @brief Structure for lt1pa01 device
*/
struct lt1pa01_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 lt1pa01_open_als(FAR struct file *filep);
static int lt1pa01_open_prox(FAR struct file *filep);
static int lt1pa01_close_als(FAR struct file *filep);
static int lt1pa01_close_prox(FAR struct file *filep);
static ssize_t lt1pa01_read_als(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t lt1pa01_read_prox(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t lt1pa01_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int lt1pa01_ioctl_als(FAR struct file *filep, int cmd,
unsigned long arg);
static int lt1pa01_ioctl_prox(FAR struct file *filep, int cmd,
unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
/* Ambient light sensor */
static const struct file_operations g_lt1pa01alsfops =
{
lt1pa01_open_als, /* open */
lt1pa01_close_als, /* close */
lt1pa01_read_als, /* read */
lt1pa01_write, /* write */
0, /* seek */
lt1pa01_ioctl_als, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Proximity sensor */
static const struct file_operations g_lt1pa01proxfops =
{
lt1pa01_open_prox, /* open */
lt1pa01_close_prox, /* close */
lt1pa01_read_prox, /* read */
lt1pa01_write, /* write */
0, /* seek */
lt1pa01_ioctl_prox, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* SCU instructions for pick ambient light sensing data. */
static const uint16_t g_lt1pa01alsinst[] =
{
SCU_INST_SEND(LT1PA01_ALS_DATA_HB),
SCU_INST_RECV(LT1PA01_ALS_BYTESPERSAMPLE) | SCU_INST_LAST,
};
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
/* SCU instructions for pick proximity sensing data. */
static const uint16_t g_lt1pa01proxinst[] =
{
SCU_INST_SEND(LT1PA01_PROX_DATA),
SCU_INST_RECV(LT1PA01_PROX_BYTESPERSAMPLE) | SCU_INST_LAST,
};
#endif
/* Reference count */
static int g_als_refcnt = 0;
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
static int g_prox_refcnt = 0;
#endif
/* Sequencer instance */
static struct seq_s *g_als_seq = NULL;
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
static struct seq_s *g_prox_seq = NULL;
#endif
#ifdef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
/* Proximity interrupt config */
static uint8_t g_prox_lthreshold = LT1PA01_PROX_INT_TL_DEFAULT;
static uint8_t g_prox_hthreshold = LT1PA01_PROX_INT_TH_DEFAULT;
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: lt1pa01_getreg8
*
* Description:
* Read from an 8-bit LT1PA01 register
*
****************************************************************************/
static uint8_t lt1pa01_getreg8(FAR struct lt1pa01_dev_s *priv,
uint8_t regaddr)
{
uint8_t regval = 0;
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, &regval, 1);
return regval;
}
/****************************************************************************
* Name: lt1pa01_putreg8
*
* Description:
* Write to an 8-bit LT1PA01 register
*
****************************************************************************/
static void lt1pa01_putreg8(FAR struct lt1pa01_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: lt1pa01_checkid
*
* Description:
* Read and verify the LT1PA01 chip ID
*
****************************************************************************/
static int lt1pa01_checkid(FAR struct lt1pa01_dev_s *priv)
{
uint8_t id;
/* Read Device ID */
id = lt1pa01_getreg8(priv, LT1PA01_ID);
sninfo("LT1PA01 ID:%02X\n", id);
if ((id & LT1PA01_ID_MASK) != LT1PA01_DEVICEID)
{
/* Device ID is not Correct */
snerr("Wrong Device ID! %02x (Exp:%02x)\n", id, LT1PA01_DEVICEID);
return -ENODEV;
}
return OK;
}
/****************************************************************************
* Name: lt1pa01als_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int lt1pa01als_seqinit(FAR struct lt1pa01_dev_s *priv)
{
DEBUGASSERT(g_als_seq == NULL);
/* Open sequencer */
g_als_seq = seq_open(SEQ_TYPE_NORMAL, SCU_BUS_I2C0);
if (!g_als_seq)
{
return -ENOENT;
}
priv->seq = g_als_seq;
seq_setaddress(priv->seq, priv->addr);
/* Set instruction and sample data information to sequencer */
seq_setinstruction(priv->seq, g_lt1pa01alsinst, itemsof(g_lt1pa01alsinst));
seq_setsample(priv->seq, LT1PA01_ALS_BYTESPERSAMPLE, 0, LT1PA01_ELEMENTSIZE,
false);
return OK;
}
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
/****************************************************************************
* Name: lt1pa01prox_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int lt1pa01prox_seqinit(FAR struct lt1pa01_dev_s *priv)
{
DEBUGASSERT(g_prox_seq == NULL);
/* Open sequencer */
g_prox_seq = seq_open(SEQ_TYPE_NORMAL, SCU_BUS_I2C0);
if (!g_prox_seq)
{
return -ENOENT;
}
priv->seq = g_prox_seq;
seq_setaddress(priv->seq, priv->addr);
/* Set instruction and sample data information to sequencer */
seq_setinstruction(priv->seq, g_lt1pa01proxinst, itemsof(g_lt1pa01proxinst));
seq_setsample(priv->seq, LT1PA01_PROX_BYTESPERSAMPLE, 0, LT1PA01_ELEMENTSIZE,
false);
return OK;
}
#endif
/****************************************************************************
* Name: lt1pa01_open_als
*
* Description:
* This function is called whenever the LT1PA01 device is opened.
*
****************************************************************************/
static int lt1pa01_open_als(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
uint8_t val;
if (g_als_refcnt == 0)
{
int ret;
ret = lt1pa01als_seqinit(priv);
if (ret < 0)
{
return ret;
}
/* ALS Enable */
val = lt1pa01_getreg8(priv, LT1PA01_CONFIG1);
val |= (LT1PA01_ALS_EN | LT1PA01_ALS_ALS_RANGE2);
lt1pa01_putreg8(priv, LT1PA01_CONFIG1, val);
}
else
{
/* Set existing sequencer */
priv->seq = g_als_seq;
}
g_als_refcnt++;
return OK;
}
/****************************************************************************
* Name: lt1pa01_open_prox
*
* Description:
* This function is called whenever the LT1PA01 device is opened.
*
****************************************************************************/
static int lt1pa01_open_prox(FAR struct file *filep)
{
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
uint8_t val;
if (g_prox_refcnt == 0)
{
int ret;
ret = lt1pa01prox_seqinit(priv);
if (ret < 0)
{
return ret;
}
/* PROX Enable */
val = LT1PA01_PROX_EN | LT1PA01_PROX_SLP_100MS;
lt1pa01_putreg8(priv, LT1PA01_CONFIG0, val);
}
else
{
/* Set existing sequencer */
priv->seq = g_prox_seq;
}
g_prox_refcnt++;
#endif
return OK;
}
/****************************************************************************
* Name: lt1pa01_close_als
*
* Description:
* This routine is called when the LT1PA01 device is closed.
*
****************************************************************************/
static int lt1pa01_close_als(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
uint8_t val;
g_als_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_als_refcnt == 0)
{
/* ALS Disable */
val = lt1pa01_getreg8(priv, LT1PA01_CONFIG1);
val &= ~LT1PA01_ALS_EN;
val &= ~LT1PA01_ALS_ALS_RANGE_MASK;
lt1pa01_putreg8(priv, LT1PA01_CONFIG1, val);
seq_close(g_als_seq);
g_als_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
return OK;
}
/****************************************************************************
* Name: lt1pa01_close_prox
*
* Description:
* This routine is called when the LT1PA01 device is closed.
*
****************************************************************************/
static int lt1pa01_close_prox(FAR struct file *filep)
{
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
g_prox_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_prox_refcnt == 0)
{
/* PROX Disable */
lt1pa01_putreg8(priv, LT1PA01_CONFIG0, 0);
seq_close(g_prox_seq);
g_prox_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
#endif
return OK;
}
/****************************************************************************
* Name: lt1pa01_read_als
****************************************************************************/
static ssize_t lt1pa01_read_als(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
len = len / LT1PA01_ALS_BYTESPERSAMPLE * LT1PA01_ALS_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->minor, buffer, len);
return len;
}
/****************************************************************************
* Name: lt1pa01_read_prox
****************************************************************************/
static ssize_t lt1pa01_read_prox(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
len = len / LT1PA01_PROX_BYTESPERSAMPLE * LT1PA01_PROX_BYTESPERSAMPLE;
#ifdef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
if (len)
{
len = LT1PA01_PROX_BYTESPERSAMPLE;
*(FAR uint8_t *)buffer = lt1pa01_getreg8(priv, LT1PA01_PROX_DATA);
}
#else
len = seq_read(priv->seq, priv->minor, buffer, len);
#endif
return len;
}
/****************************************************************************
* Name: lt1pa01_write
****************************************************************************/
static ssize_t lt1pa01_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: lt1pa01_ioctl_als
****************************************************************************/
static int lt1pa01_ioctl_als(FAR struct file *filep, int cmd,
unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_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;
}
/****************************************************************************
* Name: lt1pa01_ioctl_prox
****************************************************************************/
static int lt1pa01_ioctl_prox(FAR struct file *filep, int cmd,
unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct lt1pa01_dev_s *priv = inode->i_private;
int ret = OK;
switch (cmd)
{
#ifdef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
case SNIOC_SETPROXLTHRESHOLD:
{
g_prox_lthreshold = (uint8_t)arg;
}
break;
case SNIOC_SETPROXHTHRESHOLD:
{
g_prox_hthreshold = (uint8_t)arg;
}
break;
case SNIOC_STARTPROXMEASUREMENT:
{
uint8_t val;
/* PROX Interrupt setting */
lt1pa01_putreg8(priv, LT1PA01_PROX_INT_TL, g_prox_lthreshold);
lt1pa01_putreg8(priv, LT1PA01_PROX_INT_TH, g_prox_hthreshold);
val = LT1PA01_PORX_INT_PRST2 | LT1PA01_INT_CFG_ALS_OR_PROX;
lt1pa01_putreg8(priv, LT1PA01_INTCONFIG, val);
val = lt1pa01_getreg8(priv, LT1PA01_CONFIG1);
val |= LT1PA01_INT_ALG_COMPARATOR;
lt1pa01_putreg8(priv, LT1PA01_CONFIG1, val);
/* PROX Enable */
val = LT1PA01_PROX_EN | LT1PA01_PROX_SLP_100MS;
lt1pa01_putreg8(priv, LT1PA01_CONFIG0, val);
}
break;
case SNIOC_STOPPROXMEASUREMENT:
{
/* PROX Disable */
lt1pa01_putreg8(priv, LT1PA01_CONFIG1, 0);
}
break;
case SNIOC_GETINTSTATUS:
{
FAR uint8_t intstatus = lt1pa01_getreg8(priv, LT1PA01_INTCONFIG);
*(FAR uint8_t *)(uintptr_t)arg = intstatus;
sninfo("Get proximity IntStatus 0x%02x\n", intstatus);
}
break;
#endif
default:
{
if (_SCUIOCVALID(cmd))
{
#ifndef CONFIG_LT1PA01_PROXIMITY_INTERRUPT
/* Redirect SCU commands */
ret = seq_ioctl(priv->seq, priv->minor, cmd, arg);
#else
snerr("Unregisted SCU sequencer cmd: %d\n", cmd);
ret = - ENOTTY;
#endif
}
else
{
snerr("Unrecognized cmd: %d\n", cmd);
ret = - ENOTTY;
}
}
break;
}
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lt1pa01_init
*
* Description:
* Initialize the LT1PA01 device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* LT1PA01
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int lt1pa01_init(FAR struct i2c_master_s *i2c, int port)
{
FAR struct lt1pa01_dev_s tmp;
FAR struct lt1pa01_dev_s *priv = &tmp;
int ret;
/* Setup temporary device structure for initialization */
priv->i2c = i2c;
priv->addr = LT1PA01_ADDR;
priv->port = port;
/* Check Device ID */
ret = lt1pa01_checkid(priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
return ret;
}
/* Software reset */
lt1pa01_putreg8(priv, LT1PA01_CONFIG3, LT1PA01_SW_RESET);
/* Power-up and Brown-out Reset */
lt1pa01_putreg8(priv, LT1PA01_INTCONFIG, 0);
return OK;
}
/****************************************************************************
* Name: lt1pa01als_register
*
* Description:
* Register the LT1PA01 ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* LT1PA01
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int lt1pa01als_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct lt1pa01_dev_s *priv;
char path[16];
int ret;
/* Initialize the LT1PA01 device structure */
priv = (FAR struct lt1pa01_dev_s *)
kmm_malloc(sizeof(struct lt1pa01_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = LT1PA01_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_lt1pa01alsfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
return ret;
}
/****************************************************************************
* Name: lt1pa01prox_register
*
* Description:
* Register the LT1PA01 proximity sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/proxim0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* LT1PA01
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int lt1pa01prox_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct lt1pa01_dev_s *priv;
char path[16];
int ret;
/* Initialize the LT1PA01 device structure */
priv = (FAR struct lt1pa01_dev_s *)
kmm_malloc(sizeof(struct lt1pa01_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = LT1PA01_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_lt1pa01proxfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
sninfo("LT1PA01 proximity sensor driver loaded successfully!\n");
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_LT1PA01_SCU */

View File

@ -0,0 +1,989 @@
/****************************************************************************
* drivers/sensors/rpr0521rs_scu.c
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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 <nuttx/config.h>
#include <stdlib.h>
#include <stdio.h>
#include <fixedmath.h>
#include <errno.h>
#include <debug.h>
#include <semaphore.h>
#include <arch/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/rpr0521rs.h>
#include <nuttx/irq.h>
#include <arch/chip/scu.h>
#if defined(CONFIG_I2C) && defined(CONFIG_RPR0521RS) && defined(CONFIG_CXD56_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define RPR0521RS_ADDR 0x38 /* I2C Slave Address */
#define RPR0521RS_MANUFACTID 0xE0 /* Manufact ID */
#define RPR0521RS_PARTID 0x0A /* Part ID */
#define RPR0521RS_ALS_BYTESPERSAMPLE 4
#define RPR0521RS_PS_BYTESPERSAMPLE 2
#define RPR0521RS_ELEMENTSIZE 0
/* RPR0521RS Registers */
#define RPR0521RS_SYSTEM_CONTROL 0x40
#define RPR0521RS_MODE_CONTROL 0x41
#define RPR0521RS_ALS_PS_CONTROL 0x42
#define RPR0521RS_PS_CONTROL 0x43
#define RPR0521RS_PS_DATA_LSB 0x44
#define RPR0521RS_ALS_DATA0_LSB 0x46
#define RPR0521RS_INTERRUPT 0x4A
#define RPR0521RS_PS_TH_LSB 0x4B
#define RPR0521RS_PS_TL_LSB 0x4D
#define RPR0521RS_MANUFACT_ID 0x92
/* Register SYSTEM_CONTROL */
#define RPR0521RS_SYSTEM_CONTROL_INT_RESET (1 << 6)
/* Register MODE_CONTROL */
#define RPR0521RS_MODE_CONTROL_ALS_EN (1 << 7)
#define RPR0521RS_MODE_CONTROL_PS_EN (1 << 6)
#define RPR0521RS_MODE_CONTROL_MEASTIME_100_100MS (6 << 0)
#define RPR0521RS_MODE_CONTROL_MEASTIME_STANDBY (0 << 0)
/* Register ALS_PS_CONTROL */
#define RPR0521RS_ALS_PS_CONTROL_LED_CURRENT_100MA (2 << 0)
#define RPR0521RS_ALS_PS_CONTROL_DATA1_GAIN_X1 (0 << 2)
#define RPR0521RS_ALS_PS_CONTROL_DATA0_GAIN_X1 (0 << 4)
/* Register PS_CONTROL */
#define RPR0521RS_PS_CONTROL_PS_GAINX1 (0 << 4)
#define RPR0521RS_PS_CONTROL_PS_PERSISTENCE_2 (2 << 0)
/* Register INTERRUPT */
#define RPR0521RS_INTERRUPT_PS_INT_STATUS (1 << 7)
#define RPR0521RS_INTERRUPT_ALS_INT_STATUS (1 << 6)
#define RPR0521RS_INTERRUPT_INT_MODE_PS_TH (0 << 4)
#define RPR0521RS_INTERRUPT_INT_MODE_PS_HYSTERESIS (1 << 4)
#define RPR0521RS_INTERRUPT_INT_MODE_PS_OUTOFRANGE (2 << 4)
#define RPR0521RS_INTERRUPT_INT_ASSERT_KEEP_ACTIVE (0 << 3)
#define RPR0521RS_INTERRUPT_INT_LATCH_DISABLE (1 << 2)
#define RPR0521RS_INTERRUPT_INT_TRIG_PS (1 << 0)
#define RPR0521RS_INTERRUPT_INT_TRIG_INACTIVE (0 << 0)
/* PS_TH default value */
#define RPR0521RS_PS_TH_DEFAULT 0x0300
#define SETMODECONTROL_TYPE_PS 0
#define SETMODECONTROL_TYPE_ALS 1
#ifndef itemsof
# define itemsof(array) (sizeof(array)/sizeof(array[0]))
#endif
/****************************************************************************
* Private Type Definitions
****************************************************************************/
/**
* @brief Structure for rpr0521rs device
*/
struct rpr0521rs_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 rpr0521rs_open_als(FAR struct file *filep);
static int rpr0521rs_open_ps(FAR struct file *filep);
static int rpr0521rs_close_als(FAR struct file *filep);
static int rpr0521rs_close_ps(FAR struct file *filep);
static ssize_t rpr0521rs_read_als(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t rpr0521rs_read_ps(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t rpr0521rs_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int rpr0521rs_ioctl_als(FAR struct file *filep, int cmd,
unsigned long arg);
static int rpr0521rs_ioctl_ps(FAR struct file *filep, int cmd,
unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
/* Ambient light sensor */
static const struct file_operations g_rpr0521rsalsfops =
{
rpr0521rs_open_als, /* open */
rpr0521rs_close_als, /* close */
rpr0521rs_read_als, /* read */
rpr0521rs_write, /* write */
0, /* seek */
rpr0521rs_ioctl_als, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* Proximity sensor */
static const struct file_operations g_rpr0521rspsfops =
{
rpr0521rs_open_ps, /* open */
rpr0521rs_close_ps, /* close */
rpr0521rs_read_ps, /* read */
rpr0521rs_write, /* write */
0, /* seek */
rpr0521rs_ioctl_ps, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
0, /* poll */
#endif
0 /* unlink */
};
/* SCU instructions for pick ambient light sensing data. */
static const uint16_t g_rpr0521rsalsinst[] =
{
SCU_INST_SEND(RPR0521RS_ALS_DATA0_LSB),
SCU_INST_RECV(RPR0521RS_ALS_BYTESPERSAMPLE) | SCU_INST_LAST,
};
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
/* SCU instructions for pick proximity sensing data. */
static const uint16_t g_rpr0521rspsinst[] =
{
SCU_INST_SEND(RPR0521RS_PS_DATA_LSB),
SCU_INST_RECV(RPR0521RS_PS_BYTESPERSAMPLE) | SCU_INST_LAST,
};
#endif
/* Reference count */
static int g_als_refcnt = 0;
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
static int g_ps_refcnt = 0;
#endif
/* Sequencer instance */
static struct seq_s *g_als_seq = NULL;
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
static struct seq_s *g_ps_seq = NULL;
#endif
/* Proximity interrupt config */
static uint16_t g_ps_threshold = RPR0521RS_PS_TH_DEFAULT;
static uint8_t g_ps_persistence = RPR0521RS_PS_CONTROL_PS_PERSISTENCE_2;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: rpr0521rs_getreg8
*
* Description:
* Read from an 8-bit RPR0521RS register
*
****************************************************************************/
static uint8_t rpr0521rs_getreg8(FAR struct rpr0521rs_dev_s *priv,
uint8_t regaddr)
{
uint8_t regval = 0;
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, &regval, 1);
return regval;
}
/****************************************************************************
* Name: rpr0521rs_putreg8
*
* Description:
* Write to an 8-bit RPR0521RS register
*
****************************************************************************/
static void rpr0521rs_putreg8(FAR struct rpr0521rs_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);
}
#ifdef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
/****************************************************************************
* Name: rpr0521rs_getreg16
*
* Description:
* Read from an 16-bit RPR0521RS register
*
****************************************************************************/
static uint16_t rpr0521rs_getreg16(FAR struct rpr0521rs_dev_s *priv,
uint8_t regaddr)
{
uint16_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(2) | SCU_INST_LAST;
scu_i2ctransfer(priv->port, priv->addr, inst, 2, (FAR uint8_t *)&regval, 2);
return regval;
}
/****************************************************************************
* Name: rpr0521rs_putreg16
*
* Description:
* Write to an 16-bit RPR0521RS register
*
****************************************************************************/
static void rpr0521rs_putreg16(FAR struct rpr0521rs_dev_s *priv,
uint8_t regaddr, uint16_t regval)
{
uint16_t inst[3];
/* Send register address and set the value */
inst[0] = SCU_INST_SEND(regaddr);
inst[1] = SCU_INST_SEND((uint8_t)(regval & 0xff));
inst[2] = SCU_INST_SEND((uint8_t)(regval >> 8)) | SCU_INST_LAST;
scu_i2ctransfer(priv->port, priv->addr, inst, 3, NULL, 0);
}
#endif
/****************************************************************************
* Name: rpr0521rs_checkid
*
* Description:
* Read and verify the RPR0521RS chip ID
*
****************************************************************************/
static int rpr0521rs_checkid(FAR struct rpr0521rs_dev_s *priv)
{
uint8_t id;
/* Read Manufact ID */
id = rpr0521rs_getreg8(priv, RPR0521RS_MANUFACT_ID);
if (id != RPR0521RS_MANUFACTID)
{
/* Manufact ID is not Correct */
snerr("Wrong Manufact ID! %02x\n", id);
return -ENODEV;
}
/* Read Part ID */
id = rpr0521rs_getreg8(priv, RPR0521RS_SYSTEM_CONTROL);
if ((id & 0x3F) != RPR0521RS_PARTID)
{
/* Part ID is not Correct */
snerr("Wrong Part ID! %02x\n", id);
return -ENODEV;
}
return OK;
}
/****************************************************************************
* Name: rpr0521rs_setmodecontrol
*
* Description:
* Set MODE_CONTROL register
*
****************************************************************************/
static void rpr0521rs_setmodecontrol(FAR struct rpr0521rs_dev_s *priv,
uint8_t type, bool enable)
{
uint8_t val;
uint8_t checkbit;
uint8_t setbit;
irqstate_t flags;
if (type == SETMODECONTROL_TYPE_PS)
{
checkbit = RPR0521RS_MODE_CONTROL_ALS_EN;
setbit = RPR0521RS_MODE_CONTROL_PS_EN;
}
else
{
checkbit = RPR0521RS_MODE_CONTROL_PS_EN;
setbit = RPR0521RS_MODE_CONTROL_ALS_EN;
}
flags = enter_critical_section();
val = rpr0521rs_getreg8(priv, RPR0521RS_MODE_CONTROL);
if (val & checkbit)
{
if (enable)
{
val = setbit | checkbit | RPR0521RS_MODE_CONTROL_MEASTIME_100_100MS;
}
else
{
val = checkbit | RPR0521RS_MODE_CONTROL_MEASTIME_100_100MS;
}
}
else
{
if (enable)
{
val = setbit | RPR0521RS_MODE_CONTROL_MEASTIME_100_100MS;
}
else
{
val = RPR0521RS_MODE_CONTROL_MEASTIME_STANDBY;
}
}
rpr0521rs_putreg8(priv, RPR0521RS_MODE_CONTROL, val);
leave_critical_section(flags);
}
/****************************************************************************
* Name: rpr0521rsals_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int rpr0521rsals_seqinit(FAR struct rpr0521rs_dev_s *priv)
{
DEBUGASSERT(g_als_seq == NULL);
/* Open sequencer */
g_als_seq = seq_open(SEQ_TYPE_NORMAL, SCU_BUS_I2C0);
if (!g_als_seq)
{
return -ENOENT;
}
priv->seq = g_als_seq;
seq_setaddress(priv->seq, priv->addr);
/* Set instruction and sample data information to sequencer */
seq_setinstruction(priv->seq, g_rpr0521rsalsinst, itemsof(g_rpr0521rsalsinst));
seq_setsample(priv->seq, RPR0521RS_ALS_BYTESPERSAMPLE, 0, RPR0521RS_ELEMENTSIZE,
false);
return OK;
}
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
/****************************************************************************
* Name: rpr0521rsps_seqinit
*
* Description:
* Initialize SCU sequencer.
*
****************************************************************************/
static int rpr0521rsps_seqinit(FAR struct rpr0521rs_dev_s *priv)
{
DEBUGASSERT(g_ps_seq == NULL);
/* Open sequencer */
g_ps_seq = seq_open(SEQ_TYPE_NORMAL, SCU_BUS_I2C0);
if (!g_ps_seq)
{
return -ENOENT;
}
priv->seq = g_ps_seq;
seq_setaddress(priv->seq, priv->addr);
/* Set instruction and sample data information to sequencer */
seq_setinstruction(priv->seq, g_rpr0521rspsinst, itemsof(g_rpr0521rspsinst));
seq_setsample(priv->seq, RPR0521RS_PS_BYTESPERSAMPLE, 0, RPR0521RS_ELEMENTSIZE,
false);
return OK;
}
#endif
/****************************************************************************
* Name: rpr0521rs_open_als
*
* Description:
* This function is called whenever the RPR0521RS device is opened.
*
****************************************************************************/
static int rpr0521rs_open_als(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
if (g_als_refcnt == 0)
{
int ret;
ret = rpr0521rsals_seqinit(priv);
if (ret < 0)
{
return ret;
}
rpr0521rs_setmodecontrol(priv, SETMODECONTROL_TYPE_ALS, true);
}
else
{
/* Set existing sequencer */
priv->seq = g_als_seq;
}
g_als_refcnt++;
return OK;
}
/****************************************************************************
* Name: rpr0521rs_open_ps
*
* Description:
* This function is called whenever the RPR0521RS device is opened.
*
****************************************************************************/
static int rpr0521rs_open_ps(FAR struct file *filep)
{
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
if (g_ps_refcnt == 0)
{
int ret;
ret = rpr0521rsps_seqinit(priv);
if (ret < 0)
{
return ret;
}
rpr0521rs_setmodecontrol(priv, SETMODECONTROL_TYPE_PS, true);
}
else
{
/* Set existing sequencer */
priv->seq = g_ps_seq;
}
g_ps_refcnt++;
#endif
return OK;
}
/****************************************************************************
* Name: rpr0521rs_close_als
*
* Description:
* This routine is called when the RPR0521RS device is closed.
*
****************************************************************************/
static int rpr0521rs_close_als(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
g_als_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_als_refcnt == 0)
{
rpr0521rs_setmodecontrol(priv, SETMODECONTROL_TYPE_ALS, false);
seq_close(g_als_seq);
g_als_seq = NULL;
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
return OK;
}
/****************************************************************************
* Name: rpr0521rs_close_ps
*
* Description:
* This routine is called when the RPR0521RS device is closed.
*
****************************************************************************/
static int rpr0521rs_close_ps(FAR struct file *filep)
{
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
g_ps_refcnt--;
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_STOP, 0);
if (g_ps_refcnt == 0)
{
rpr0521rs_setmodecontrol(priv, SETMODECONTROL_TYPE_PS, false);
if (g_ps_seq)
{
seq_close(g_ps_seq);
g_ps_seq = NULL;
}
}
else
{
(void) seq_ioctl(priv->seq, priv->minor, SCUIOC_FREEFIFO, 0);
}
#endif
return OK;
}
/****************************************************************************
* Name: rpr0521rs_read_als
****************************************************************************/
static ssize_t rpr0521rs_read_als(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
len = len / RPR0521RS_ALS_BYTESPERSAMPLE * RPR0521RS_ALS_BYTESPERSAMPLE;
len = seq_read(priv->seq, priv->minor, buffer, len);
return len;
}
/****************************************************************************
* Name: rpr0521rs_read_ps
****************************************************************************/
static ssize_t rpr0521rs_read_ps(FAR struct file *filep, FAR char *buffer,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
len = len / RPR0521RS_PS_BYTESPERSAMPLE * RPR0521RS_PS_BYTESPERSAMPLE;
#ifdef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
if (len)
{
len = RPR0521RS_PS_BYTESPERSAMPLE;
*(FAR uint16_t *)buffer = rpr0521rs_getreg16(priv, RPR0521RS_PS_DATA_LSB);
}
#else
len = seq_read(priv->seq, priv->minor, buffer, len);
#endif
return len;
}
/****************************************************************************
* Name: rpr0521rs_write
****************************************************************************/
static ssize_t rpr0521rs_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Name: rpr0521rs_ioctl_als
****************************************************************************/
static int rpr0521rs_ioctl_als(FAR struct file *filep, int cmd,
unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_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;
}
/****************************************************************************
* Name: rpr0521rs_ioctl_ps
****************************************************************************/
static int rpr0521rs_ioctl_ps(FAR struct file *filep, int cmd,
unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rpr0521rs_dev_s *priv = inode->i_private;
int ret = OK;
#ifdef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
uint8_t val;
#endif
switch (cmd)
{
case SNIOC_SETTHRESHOLD:
{
g_ps_threshold = (uint16_t)arg;
}
break;
case SNIOC_SETPERSISTENCE:
{
g_ps_persistence = (uint8_t)arg;
}
break;
case SNIOC_STARTMEASUREMENT:
{
#ifdef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
val = RPR0521RS_PS_CONTROL_PS_GAINX1 | (g_ps_persistence & 0x0f);
rpr0521rs_putreg8(priv, RPR0521RS_PS_CONTROL, val);
rpr0521rs_putreg16(priv, RPR0521RS_PS_TH_LSB,
g_ps_threshold & 0x0fff);
val = RPR0521RS_INTERRUPT_INT_MODE_PS_TH |
RPR0521RS_INTERRUPT_INT_ASSERT_KEEP_ACTIVE |
RPR0521RS_INTERRUPT_INT_LATCH_DISABLE |
RPR0521RS_INTERRUPT_INT_TRIG_PS;
rpr0521rs_putreg8(priv, RPR0521RS_INTERRUPT, val);
rpr0521rs_setmodecontrol(priv, SETMODECONTROL_TYPE_PS, true);
#endif
}
break;
case SNIOC_STOPMEASUREMENT:
{
#ifdef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
rpr0521rs_setmodecontrol(priv, SETMODECONTROL_TYPE_PS, false);
val = RPR0521RS_INTERRUPT_INT_TRIG_INACTIVE;
rpr0521rs_putreg8(priv, RPR0521RS_INTERRUPT, val);
val = RPR0521RS_SYSTEM_CONTROL_INT_RESET;
rpr0521rs_putreg8(priv, RPR0521RS_SYSTEM_CONTROL, val);
#endif
}
break;
case SNIOC_GETINTSTATUS:
{
FAR uint8_t intstatus = rpr0521rs_getreg8(priv, RPR0521RS_INTERRUPT);
*(FAR uint8_t *)(uintptr_t)arg = intstatus;
sninfo("Get proximity IntStatus 0x%02x\n", intstatus);
}
break;
default:
{
if (_SCUIOCVALID(cmd))
{
#ifndef CONFIG_RPR0521RS_PROXIMITY_INTERRUPT
/* Redirect SCU commands */
ret = seq_ioctl(priv->seq, priv->minor, cmd, arg);
#else
snerr("Unregisted SCU sequencer cmd: %d\n", cmd);
ret = - ENOTTY;
#endif
}
else
{
snerr("Unrecognized cmd: %d\n", cmd);
ret = - ENOTTY;
}
}
break;
}
return ret;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: rpr0521rs_init
*
* Description:
* Initialize the RPR0521RS device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* RPR0521RS
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int rpr0521rs_init(FAR struct i2c_master_s *i2c, int port)
{
FAR struct rpr0521rs_dev_s tmp;
FAR struct rpr0521rs_dev_s *priv = &tmp;
int ret;
uint8_t val;
/* Setup temporary device structure for initialization */
priv->i2c = i2c;
priv->addr = RPR0521RS_ADDR;
priv->port = port;
/* Check Device ID */
ret = rpr0521rs_checkid(priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
return ret;
}
/* ALS initialize */
val = RPR0521RS_ALS_PS_CONTROL_DATA0_GAIN_X1 |
RPR0521RS_ALS_PS_CONTROL_DATA1_GAIN_X1 |
RPR0521RS_ALS_PS_CONTROL_LED_CURRENT_100MA;
rpr0521rs_putreg8(priv, RPR0521RS_ALS_PS_CONTROL, val);
/* PS initialize */
val = RPR0521RS_PS_CONTROL_PS_GAINX1;
rpr0521rs_putreg8(priv, RPR0521RS_PS_CONTROL, val);
val = RPR0521RS_INTERRUPT_INT_TRIG_INACTIVE;
rpr0521rs_putreg8(priv, RPR0521RS_INTERRUPT, val);
return OK;
}
/****************************************************************************
* Name: rpr0521rsals_register
*
* Description:
* Register the RPR0521RS ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* RPR0521RS
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int rpr0521rsals_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct rpr0521rs_dev_s *priv;
char path[16];
int ret;
/* Initialize the RPR0521RS device structure */
priv = (FAR struct rpr0521rs_dev_s *)
kmm_malloc(sizeof(struct rpr0521rs_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = RPR0521RS_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_rpr0521rsalsfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
return ret;
}
/****************************************************************************
* Name: rpr0521rsps_register
*
* Description:
* Register the RPR0521RS proximity sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/proxim0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* RPR0521RS
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int rpr0521rsps_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port)
{
FAR struct rpr0521rs_dev_s *priv;
char path[16];
int ret;
/* Initialize the RPR0521RS device structure */
priv = (FAR struct rpr0521rs_dev_s *)
kmm_malloc(sizeof(struct rpr0521rs_dev_s));
if (!priv)
{
snerr("Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = RPR0521RS_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_rpr0521rspsfops, 0666, priv);
if (ret < 0)
{
snerr("Failed to register driver: %d\n", ret);
kmm_free(priv);
}
sninfo("RPR0521RS proximity sensor driver loaded successfully!\n");
return ret;
}
#endif /* CONFIG_I2C && CONFIG_RPR0521RS && CONFIG_CXD56_SCU */

View File

@ -83,6 +83,23 @@ config SENSORS_BMI160_SPI
---help---
Enables support for the SPI interface
endchoice
choice
prompt "I2C Address"
default BMI160_I2C_ADDR_68
config BMI160_I2C_ADDR_68
bool "0x68"
---help---
Default address.
If SDO pin is pulled to VDDIO, use 0x69
config BMI160_I2C_ADDR_69
bool "0x69"
---help---
If SDO pin is pulled to VDDIO, use 0x69
endchoice
endif

View File

@ -57,7 +57,18 @@
****************************************************************************/
#define DEVID 0xd1
#define BMI160_I2C_ADDR 0x68 /* If SDO pin is pulled to VDDIO, use 0x69 */
/* I2C Address
*
* NOTE: If SDO pin is pulled to VDDIO, use 0x69
*/
#ifdef CONFIG_BMI160_I2C_ADDR_68
#define BMI160_I2C_ADDR 0x68
#else
#define BMI160_I2C_ADDR 0x69
#endif
#define BMI160_I2C_FREQ 400000
#define BMI160_CHIP_ID (0x00) /* Chip ID */

View File

@ -0,0 +1,151 @@
/****************************************************************************
* include/nuttx/sensors/apds9930.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_APDS9930_H
#define __INCLUDE_NUTTX_SENSORS_APDS9930_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && (defined(SENSORS_CONFIG_APDS9930) || defined(SENSORS_CONFIG_APDS9930_SCU))
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration */
/* Prerequisites:
*
* CONFIG_APDS9930
* Enables support for the APDS9930 driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/* IOCTL Commands */
/* These commands are valid for CONFIG_APDS9930_PROXIMITY_INTERRUPT=y */
#define SNIOC_SETPSLTHRESHOLD _SNIOC(0x0001) /* Set low threshold */
#define SNIOC_SETPSHTHRESHOLD _SNIOC(0x0002) /* Set high threshold */
#define SNIOC_SETPSPERSISTENCE _SNIOC(0x0003) /* Set persistence(0-15) */
#define SNIOC_STARTPSMEASUREMENT _SNIOC(0x0004) /* Start measurement */
#define SNIOC_STOPPSMEASUREMENT _SNIOC(0x0005) /* Stop measurement */
#define SNIOC_GETINTSTATUS _SNIOC(0x0006) /* Get interrupt status */
#define SNIOC_CLEARPSINT _SNIOC(0x0007) /* Clear interrupt */
/****************************************************************************
* Name: apds9930_init
*
* Description:
* Initialize APDS9930 proximity and ambient light sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* APDS9930
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int apds9930_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: apds9930als_register
*
* Description:
* Register the APDS9930 ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* APDS9930
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int apds9930als_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: apds9930ps_register
*
* Description:
* Register the APDS9930 proximity sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/proxim0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* APDS9930
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int apds9930ps_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_SENSORS_APDS9930 */
#endif /* __INCLUDE_NUTTX_SENSORS_APDS9930_H */

View File

@ -0,0 +1,118 @@
/****************************************************************************
* include/nuttx/sensors/bh1721fvc.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_BH1721FVC_H
#define __INCLUDE_NUTTX_SENSORS_BH1721FVC_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BH1721FVC) || defined(CONFIG_SENORS_BH1721FVC_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_BH1721FVC
* Enables support for the BH1721FVC driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: bh1721fvc_init
*
* Description:
* Initialize BH1721FVC proximity and ambient light sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BH1721FVC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1721fvc_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: bh1721fvcals_register
*
* Description:
* Register the BH1721FVC ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* BH1721FVC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1721fvc_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_BH1721FVC */
#endif /* __INCLUDE_NUTTX_SENSORS_BH1721FVC_H */

View File

@ -0,0 +1,118 @@
/****************************************************************************
* include/nuttx/sensors/bh1745nuc.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_BH1745NUC_H
#define __INCLUDE_NUTTX_SENSORS_BH1745NUC_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && (defined(CONFIG_SENSORS_BH1745NUC) || defined(CONFIG_SENSORS_BH1745NUC_SRC))
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_BH1745NUC
* Enables support for the BH1745NUC driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: bh1745nuc_init
*
* Description:
* Initialize BH1745NUC color sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BH1745NUC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1745nuc_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: bh1745nuc_register
*
* Description:
* Register the BH1745NUC 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
* BH1745NUC
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bh1745nuc_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_BH1745NUC */
#endif /* __INCLUDE_NUTTX_SENSORS_BH1745NUC_H */

View File

@ -0,0 +1,118 @@
/****************************************************************************
* include/nuttx/sensors/bm1383glv.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_BM1383GLV_H
#define __INCLUDE_NUTTX_SENSORS_BM1383GLV_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BM1383GLV) || defined(CONFIG_SENSORS_BM1383GLV_SCU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_BM1383GLV
* Enables support for the BM1383GLV driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: bm1383glv_init
*
* Description:
* Initialize BM1383GLV pressure sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BM1383GLV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1383glv_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: bm1383glv_register
*
* Description:
* Register the BM1383GLV character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/press0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* BM1383GLV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1383glv_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_BM1383GLV */
#endif /* __INCLUDE_NUTTX_SENSORS_BM1383GLV_H */

View File

@ -0,0 +1,118 @@
/****************************************************************************
* include/nuttx/sensors/bm1422gmv.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_BM1422GMV_H
#define __INCLUDE_NUTTX_SENSORS_BM1422GMV_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && (defined(CONFIG_SENSORS_BM1422GMV) || defined(CONFIG_SENSORS_BM1422GMV_SCU))
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_BM1422GMV
* Enables support for the BM1422GMV driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: bm1422gmv_init
*
* Description:
* Initialize BM1422GMV magnetic sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BM1422GMV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1422gmv_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: bm1422gmv_register
*
* Description:
* Register the BM1422GMV character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/mag0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* BM1422GMV
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bm1422gmv_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_SENSORS_BM1422GMV */
#endif /* __INCLUDE_NUTTX_SENSORS_BM1422GMV_H */

View File

@ -39,6 +39,12 @@
#include <nuttx/config.h>
#include <nuttx/fs/ioctl.h>
#if defined(CONFIG_SENSORS_BMI160) || defined(CONFIG_SENSORS_BMI160_SCU)
#ifdef CONFIG_SENSORS_BMI160_SCU_I2C
#define CONFIG_SENSORS_BMI160_I2C
#endif
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@ -79,6 +85,7 @@
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* struct 6-axis data
****************************************************************************/
@ -134,15 +141,36 @@ extern "C"
*
****************************************************************************/
#ifndef CONFIG_SENSORS_BMI160_SCU
# ifdef CONFIG_SENSORS_BMI160_I2C
int bmi160_register(FAR const char *devpath, FAR struct i2c_master_s *dev);
# else
# else /* CONFIG_BMI160_SPI */
int bmi160_register(FAR const char *devpath, FAR struct spi_dev_s *dev);
# endif
#else /* CONFIG_SENSORS_BMI160_SCU */
# ifdef CONFIG_SENSORS_BMI160_I2C
int bmi160_init(FAR struct i2c_master_s *dev, int port);
int bmi160gyro_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *dev, int port);
int bmi160accel_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *dev, int port);
# else /* CONFIG_SENSORS_BMI160_SPI */
int bmi160_init(FAR struct spi_dev_s *dev);
int bmi160gyro_register(FAR const char *devpath, int minor,
FAR struct spi_dev_s *dev);
int bmi160accel_register(FAR const char *devpath, int minor,
FAR struct spi_dev_s *dev);
# endif
#endif
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_SENSORS_BMI160 */
#endif /* __INCLUDE_NUTTX_SENSORS_BMI160_H */

View File

@ -38,7 +38,7 @@
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP280)
#if defined(CONFIG_I2C) && (defined(CONFIG_SENSORS_BMP280) || defined(CONFIG_SENSORS_BMP280_SCU))
/****************************************************************************
* Pre-processor Definitions
@ -114,31 +114,50 @@ extern "C"
struct bmp280_press_adj_s
{
uint16_t dig_p1; /** calibration P1 data */
int16_t dig_p2; /** calibration P2 data */
int16_t dig_p3; /** calibration P3 data */
int16_t dig_p4; /** calibration P4 data */
int16_t dig_p5; /** calibration P5 data */
int16_t dig_p6; /** calibration P6 data */
int16_t dig_p7; /** calibration P7 data */
int16_t dig_p8; /** calibration P8 data */
int16_t dig_p9; /** calibration P9 data */
uint16_t dig_p1; /* calibration P1 data */
int16_t dig_p2; /* calibration P2 data */
int16_t dig_p3; /* calibration P3 data */
int16_t dig_p4; /* calibration P4 data */
int16_t dig_p5; /* calibration P5 data */
int16_t dig_p6; /* calibration P6 data */
int16_t dig_p7; /* calibration P7 data */
int16_t dig_p8; /* calibration P8 data */
int16_t dig_p9; /* calibration P9 data */
};
struct bmp280_temp_adj_s
{
uint16_t dig_t1; /** calibration T1 data */
int16_t dig_t2; /** calibration T2 data */
int16_t dig_t3; /** calibration T3 data */
uint16_t dig_t1; /* calibration T1 data */
int16_t dig_t2; /* calibration T2 data */
int16_t dig_t3; /* calibration T3 data */
};
struct bmp280_meas_s
{
uint8_t msb; /** meas value MSB */
uint8_t lsb; /** meas value LSB */
uint8_t xlsb; /** meas value XLSB */
uint8_t msb; /* meas value MSB */
uint8_t lsb; /* meas value LSB */
uint8_t xlsb; /* meas value XLSB */
};
#ifdef CONFIG_SENSORS_BMP280_SCU
/****************************************************************************
* Name: bmp280_init
*
* Description:
* Initialize BMP280 pressure device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* BMP280
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int bmp280_init(FAR struct i2c_master_s *i2c, int port);
#endif
/****************************************************************************
* Name: bmp280_register
*
@ -154,7 +173,14 @@ struct bmp280_meas_s
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
#ifdef CONFIG_SENSORS_BMP280_SCU
int bmp280press_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
int bmp280temp_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#else
int bmp280_register(FAR const char *devpath, FAR struct i2c_master_s *i2c);
#endif
#undef EXTERN
#ifdef __cplusplus

View File

@ -0,0 +1,119 @@
/****************************************************************************
* include/nuttx/sensors/kx022.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_KX022_H
#define __INCLUDE_NUTTX_SENSORS_KX022_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && (defined(CONFIG_SENSORS_KX022) || defined(CONFIG_SENSORS_KX022_SCU))
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_SENSORS_KX022
* Enables support for the KX022 driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: kx022_init
*
* Description:
* Initialize KX022 accelerometer device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* KX022
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int kx022_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: kx022_register
*
* Description:
* Register the KX022 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
* KX022
* port - I2C port (0 or 1)
* seq - Sequencer instance
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int kx022_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_SENSORS_KX022 */
#endif /* __INCLUDE_NUTTX_SENSORS_KX022_H */

View File

@ -0,0 +1,149 @@
/****************************************************************************
* include/nuttx/sensors/lt1pa01.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_LT1PA01_H
#define __INCLUDE_NUTTX_SENSORS_LT1PA01_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && (defined(CONFIG_SENSORS_LT1PA01) || defined(CONFIG_SENSORS_LT1PA01_SCU))
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_LT1PA01
* Enables support for the LT1PA01 driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/* IOCTL Commands ***********************************************************
* These commands are valid for CONFIG_LT1PA01_PROXIMITY_INTERRUPT=y
*/
#define SNIOC_SETPROXLTHRESHOLD _SNIOC(0x0001) /* Set low threshold */
#define SNIOC_SETPROXHTHRESHOLD _SNIOC(0x0002) /* Set high threshold */
#define SNIOC_STARTPROXMEASUREMENT _SNIOC(0x0003) /* Start measurement */
#define SNIOC_STOPPROXMEASUREMENT _SNIOC(0x0004) /* Stop measurement */
#define SNIOC_GETINTSTATUS _SNIOC(0x0005) /* Get interrupt status */
/****************************************************************************
* Name: lt1pa01_init
*
* Description:
* Initialize LT1PA01 proximity and ambient light sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* LT1PA01
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int lt1pa01_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: lt1pa01als_register
*
* Description:
* Register the LT1PA01 ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* LT1PA01
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int lt1pa01als_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: lt1pa01prox_register
*
* Description:
* Register the LT1PA01 proximity sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/proxim0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* LT1PA01
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int lt1pa01prox_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_LT1PA01 */
#endif /* __INCLUDE_NUTTX_SENSORS_LT1PA01_H */

View File

@ -0,0 +1,147 @@
/****************************************************************************
* include/nuttx/sensors/rpr0521rs.h
*
* Copyright 2018 Sony Semiconductor Solutions 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 of Sony Semiconductor Solutions Corporation 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_RPR0521RS_H
#define __INCLUDE_NUTTX_SENSORS_RPR0521RS_H
#include <nuttx/config.h>
#if defined(CONFIG_I2C) && (defined(CONFIG_SENSORS_RPR0521RS) || defined(CONFIG_SENSORS_RPR0521RS_SCU))
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Prerequisites:
*
* CONFIG_RPR0521RS
* Enables support for the RPR0521RS driver
*/
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/* IOCTL Commands ***********************************************************/
#define SNIOC_SETTHRESHOLD _SNIOC(0x0001) /* Set proximity threshold */
#define SNIOC_SETPERSISTENCE _SNIOC(0x0002) /* Set proximity interrupt persistence */
#define SNIOC_STARTMEASUREMENT _SNIOC(0x0003) /* Start proximity measurement */
#define SNIOC_STOPMEASUREMENT _SNIOC(0x0004) /* Stop proximity measurement */
#define SNIOC_GETINTSTATUS _SNIOC(0x0005) /* Get proximity interrupt status */
/****************************************************************************
* Name: rpr0521rs_init
*
* Description:
* Initialize RPR0521RS proximity and ambient light sensor device
*
* Input Parameters:
* i2c - An instance of the I2C interface to use to communicate with
* RPR0521RS
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int rpr0521rs_init(FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: rpr0521rsals_register
*
* Description:
* Register the RPR0521RS ambient light sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/light0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* RPR0521RS
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int rpr0521rsals_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
/****************************************************************************
* Name: rpr0521rsps_register
*
* Description:
* Register the RPR0521RS proximity sensor character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/proxim0"
* minor - minor device number
* i2c - An instance of the I2C interface to use to communicate with
* RPR0521RS
* port - I2C port (0 or 1)
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int rpr0521rsps_register(FAR const char *devpath, int minor,
FAR struct i2c_master_s *i2c, int port);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_I2C && CONFIG_SENSORS_RPR0521RS */
#endif /* __INCLUDE_NUTTX_SENSORS_RPR0521RS_H */