Merged in Justifa/nuttx (pull request #883)

Add support for AS726X spectral sensor

* configs/nucleo-l476rg/src/stm32_appinit.c Add I2C tool to board init

* configs/nucleo-l476rg/src/stm32_bmp180.c Fix comment

* configs/stm32f103-minimum/src/stm32_veml6070.c Fix name in error message

* drivers/sensor, include/nuttx/sensors and configs/nucleo-l476rg: Add support for AS726X spectral sensor

    Implement driver for AS726X spectral

    read as726x V,B,G,Y,O,R channel

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Fabian Justi 2019-06-05 12:50:03 +00:00 committed by Gregory Nutt
parent 95c168ccc9
commit ff5f1945ec
10 changed files with 830 additions and 2 deletions

View File

@ -93,6 +93,10 @@ ifeq ($(CONFIG_SENSORS_LSM303AGR),y)
CSRCS += stm32_lsm303agr.c
endif
ifeq ($(CONFIG_SENSORS_AS726X),y)
CSRCS += stm32_as726x.c
endif
ifeq ($(CONFIG_SENSORS_BMP180),y)
CSRCS += stm32_bmp180.c
endif

View File

@ -421,6 +421,18 @@ int stm32l4_qencoder_initialize(FAR const char *devpath, int timer);
int stm32l4_cc1101_initialize(void);
#endif
/****************************************************************************
* Name: stm32_as726xinitialize
*
* Description:
* Called to configure an I2C and to register AS726X.
*
****************************************************************************/
#ifdef CONFIG_SENSORS_AS726X
int stm32_as726xinitialize(FAR const char *devpath);
#endif
/****************************************************************************
* Name: stm32_bmp180initialize
*

View File

@ -82,6 +82,59 @@
# define MMCSD_MINOR 0
#endif
/****************************************************************************
* Name: stm32_i2c_register
*
* Description:
* Register one I2C drivers for the I2C tool.
*
****************************************************************************/
#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL)
static void stm32_i2c_register(int bus)
{
FAR struct i2c_master_s *i2c;
int ret;
i2c = stm32l4_i2cbus_initialize(bus);
if (i2c == NULL)
{
syslog(LOG_ERR, "ERROR: Failed to get I2C%d interface\n", bus);
}
else
{
ret = i2c_register(i2c, bus);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to register I2C%d driver: %d\n",bus, ret);
stm32l4_i2cbus_uninitialize(i2c);
}
}
}
#endif
/****************************************************************************
* Name: stm32_i2ctool
*
* Description:
* Register I2C drivers for the I2C tool.
*
****************************************************************************/
#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL)
static void stm32_i2ctool(void)
{
stm32_i2c_register(1);
#if 0
stm32_i2c_register(1);
stm32_i2c_register(2);
#endif
}
#else
# define stm32_i2ctool()
#endif
/****************************************************************************
* Name: board_app_initialize
*
@ -112,6 +165,11 @@ int board_app_initialize(uintptr_t arg)
#ifdef HAVE_RTC_DRIVER
FAR struct rtc_lowerhalf_s *rtclower;
#endif
#if defined(CONFIG_I2C) && defined(CONFIG_SYSTEM_I2CTOOL)
stm32_i2ctool();
#endif
#ifdef CONFIG_SENSORS_QENCODER
int index;
char buf[9];
@ -190,6 +248,15 @@ int board_app_initialize(uintptr_t arg)
syslog(LOG_INFO, "[boot] Initialized SDIO\n");
#endif
#ifdef CONFIG_SENSORS_AS726X
ret = stm32_as726xinitialize("/dev/spectr0");
if (ret < 0)
{
syslog(LOG_ERR, "Failed to initialize AS726X, error %d\n", ret);
return ret;
}
#endif
#ifdef CONFIG_SENSORS_BMP180
ret = stm32_bmp180initialize("/dev/press0");
if (ret < 0)

View File

@ -0,0 +1,103 @@
/************************************************************************************
* configs/nucleo-l476rg/src/stm32_as726x.c
*
* Copyright (C) 2019 Fabian Justi. All rights reserved.
* Author: Fabian Justi <Fabian.Justi@gmx.de>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor 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 <errno.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sensors/as726x.h>
#include "stm32l4.h"
#include "stm32l4_i2c.h"
#include "nucleo-l476rg.h"
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_AS726X)
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_as726xinitialize
*
* Description:
* Initialize and register the AS726X Spectral sensor.
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/spectr0"
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
************************************************************************************/
int stm32_as726xinitialize(FAR const char *devpath)
{
FAR struct i2c_master_s *i2c;
int ret;
sninfo("Initializing AS726X!\n");
/* Initialize I2C */
i2c = stm32l4_i2cbus_initialize(AS726X_I2C_PORTNO);
if (!i2c)
{
return -ENODEV;
}
/* Then register the light sensor */
ret = as726x_register(devpath, i2c);
if (ret < 0)
{
snerr("ERROR: Error registering AS726X\n");
}
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_AS726X && CONFIG_STM32_I2C1 */

View File

@ -1,5 +1,5 @@
/************************************************************************************
* configs/stm32f4discovery/src/stm32_bmp180.c
* configs/nucleo-l476rg/src/stm32_bmp180.c
*
* Copyright (C) 2015 Alan Carvalho de Assis. All rights reserved.
* Author: Alan Carvalho de Assis <acassis@gmail.com>

View File

@ -96,7 +96,7 @@ int stm32_veml6070initialize(FAR const char *devpath)
ret = veml6070_register(devpath, i2c, VEML6070_I2C_DATA_LSB_CMD_ADDR);
if (ret < 0)
{
snerr("ERROR: Error registering BM180\n");
snerr("ERROR: Error registering VEML6070\n");
}
return ret;

View File

@ -23,6 +23,13 @@ config SENSORS_AS5048B
---help---
Enable driver support for the AMS AS5048B magnetic rotary encoder.
config SENSORS_AS726X
bool "AMS AS726X Spetral sensor support"
default n
select I2C
---help---
Enable driver support for the AS726X Spectral Sensor.
config SENSORS_BH1750FVI
bool "Rohm BH1750FVI Ambient Light Sensor support"
default n

View File

@ -61,6 +61,10 @@ ifeq ($(CONFIG_SENSORS_AS5048B),y)
CSRCS += as5048b.c
endif
ifeq ($(CONFIG_SENSORS_AS726X),y)
CSRCS += as726x.c
endif
ifeq ($(CONFIG_SENSORS_KXTJ9),y)
CSRCS += kxtj9.c
endif

468
drivers/sensors/as726x.c Normal file
View File

@ -0,0 +1,468 @@
/****************************************************************************
* drivers/sensors/as726x.c
* Character driver for the AS7263 6-Ch NIR Spectral Sensing Engine
* and AS7262 Consumer Grade Smart 6-Channel VIS Sensor
*
* Copyright (C) 2019 Fabian Justi. All rights reserved.
* Author: Fabian Justi <Fabian.Justi@gmx.de> and
* Andreas Kurz <andreas.kurz@methodpark.de>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor 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 <errno.h>
#include <debug.h>
#include <stdlib.h>
#include <string.h>
#include <nuttx/kmalloc.h>
#include <nuttx/signal.h>
#include <nuttx/random.h>
#include <nuttx/fs/fs.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sensors/as726x.h>
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_AS726X)
/****************************************************************************
* Pre-process Definitions
****************************************************************************/
#ifndef CONFIG_AS726X_I2C_FREQUENCY
# define CONFIG_AS726X_I2C_FREQUENCY 100000
#endif
#define AS726X_INTEGRATION_TIME 50
#define AS726X_GAIN 0b01 //Set gain to 64x
#define AS726X_MEASURMENT_MODE 0b10 //One-shot reading of VBGYOR or RSTUVW
/****************************************************************************
* Private Types
****************************************************************************/
struct as726x_dev_s
{
FAR struct i2c_master_s *i2c; /* I2C interface */
uint8_t addr; /* I2C address */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static float as726x_getCalibrated(FAR struct as726x_dev_s *priv,
uint8_t regaddr);
static int16_t as726x_getChannel(FAR struct as726x_dev_s *priv,
uint8_t regaddr);
/* I2C Helpers */
static uint8_t readRegister(FAR struct as726x_dev_s *priv, uint8_t addr);
static uint8_t as726x_read8(FAR struct as726x_dev_s *priv,
uint8_t regval);
static void writeRegister(FAR struct as726x_dev_s *priv, uint8_t addr, uint8_t val);
static void as726x_write8(FAR struct as726x_dev_s *priv, uint8_t regaddr,
uint8_t regval);
/* Character driver methods */
static int as726x_open(FAR struct file *filep);
static int as726x_close(FAR struct file *filep);
static ssize_t as726x_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t as726x_write(FAR struct file *filep,
FAR const char *buffer, size_t buflen);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_as726x_fops =
{
as726x_open, /* open */
as726x_close, /* close */
as726x_read, /* read */
as726x_write, /* write */
NULL, /* seek */
NULL /* ioctl */
#ifndef CONFIG_DISABLE_POLL
, NULL /* poll */
#endif
#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS
, NULL /* unlink */
#endif
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: as726x_getCalibrated
*
* Description:
* Read calibrated value
*
****************************************************************************/
static float as726x_getCalibrated(FAR struct as726x_dev_s *priv,
uint8_t regaddr)
{
uint8_t byte0 = as726x_read8(priv, regaddr + 0);
uint8_t byte1 = as726x_read8(priv, regaddr + 1);
uint8_t byte2 = as726x_read8(priv, regaddr + 2);
uint8_t byte3 = as726x_read8(priv, regaddr + 3);
uint32_t colourData = ((uint32_t) byte0 << (8 * 3));
colourData |= ((uint32_t) byte1 << (8 * 2));
colourData |= ((uint32_t) byte2 << (8 * 1));
colourData |= ((uint32_t) byte3 << (8 * 0));
return *((float*)(&colourData));
}
/****************************************************************************
* Name: as726x_getChannel
*
* Description:
* Read colour channel
*
****************************************************************************/
static int16_t as726x_getChannel(FAR struct as726x_dev_s *priv,
uint8_t regaddr)
{
int16_t colourData = as726x_read8(priv, regaddr) << 8;
colourData |= as726x_read8(priv, regaddr + 1);
return colourData;
}
/****************************************************************************
* Name: as726x_read8
*
* Description:
* Read 8-bit register
*
****************************************************************************/
static uint8_t readRegister(FAR struct as726x_dev_s *priv, uint8_t addr)
{
struct i2c_config_s config;
uint8_t regval = 0;
int ret;
config.frequency = CONFIG_AS726X_I2C_FREQUENCY;
config.address = AS726X_I2C_ADDR;
config.addrlen = 7;
ret = i2c_write(priv->i2c, &config, &addr, 1);
if(ret < 0) {
snerr("ERROR: i2c_write failed: %d\n", ret);
return ret;
}
ret = i2c_read(priv->i2c, &config, &regval, 1);
if(ret < 0) {
snerr("ERROR: i2c_read failed: %d\n", ret);
return ret;
}
return regval;
}
static uint8_t as726x_read8(FAR struct as726x_dev_s *priv,
uint8_t regaddr)
{
uint8_t status;
status = readRegister(priv, AS72XX_SLAVE_STATUS_REG);
if ((status & AS72XX_SLAVE_RX_VALID) != 0) //There is data to be read
{
(void) readRegister(priv, AS72XX_SLAVE_READ_REG); //Read the byte but do nothing with it
}
//Wait for WRITE flag to clear
while (1)
{
status = readRegister(priv, AS72XX_SLAVE_STATUS_REG);
if ((status & AS72XX_SLAVE_TX_VALID) == 0) break; // If TX bit is clear, it is ok to write
usleep(AS726X_POLLING_DELAY);
}
// Send the virtual register address (bit 7 should be 0 to indicate we are reading a register).
writeRegister(priv, AS72XX_SLAVE_WRITE_REG, regaddr);
//Wait for READ flag to be set
while (1)
{
status = readRegister(priv, AS72XX_SLAVE_STATUS_REG);
if ((status & AS72XX_SLAVE_RX_VALID) != 0) break; // Read data is ready.
usleep(AS726X_POLLING_DELAY);
}
uint8_t incoming = readRegister(priv, AS72XX_SLAVE_READ_REG);
return incoming;
}
/****************************************************************************
* Name: as726x_write8
*
* Description:
* Write from an 8-bit register
*
****************************************************************************/
static void writeRegister(FAR struct as726x_dev_s *priv, uint8_t addr, uint8_t val)
{
struct i2c_config_s config;
uint8_t msg[2] = { 0 };
int ret;
config.frequency = CONFIG_AS726X_I2C_FREQUENCY;
config.address = AS726X_I2C_ADDR;
config.addrlen = 7;
msg[0] = addr;
msg[1] = val;
ret = i2c_write(priv->i2c, &config, msg, 2);
if (ret < 0)
{
snerr("ERROR: i2c_write failed: %d\n", ret);
return;
}
}
static void as726x_write8(FAR struct as726x_dev_s *priv, uint8_t regaddr,
uint8_t regval)
{
uint8_t status;
while (1)
{
status = readRegister(priv, AS72XX_SLAVE_STATUS_REG);
if ((status & AS72XX_SLAVE_TX_VALID) == 0) break; // No inbound TX pending at slave. Okay to write now.
usleep(AS726X_POLLING_DELAY);
}
// Send the virtual register address (setting bit 7 to indicate we are writing to a register).
writeRegister(priv, AS72XX_SLAVE_WRITE_REG, (regaddr | 0x80));
//Wait for WRITE register to be empty
while (1)
{
status = readRegister(priv, AS72XX_SLAVE_STATUS_REG);
if ((status & AS72XX_SLAVE_TX_VALID) == 0) break; // No inbound TX pending at slave. Okay to write now.
usleep(AS726X_POLLING_DELAY);
}
// Send the data to complete the operation.
writeRegister(priv, AS72XX_SLAVE_WRITE_REG, regval);
}
/****************************************************************************
* Name: as726x_open
*
* Description:
* This function is called whenever the AS726X device is opened.
*
****************************************************************************/
static int as726x_open(FAR struct file *filep)
{
return OK;
}
/****************************************************************************
* Name: as726x_close
*
* Description:
* This routine is called when the AS726X device is closed.
*
****************************************************************************/
static int as726x_close(FAR struct file *filep)
{
return OK;
}
/****************************************************************************
* Name: as726x_read
****************************************************************************/
static ssize_t as726x_read(FAR struct file *filep, FAR char *buffer,
size_t buflen)
{
FAR struct inode *inode = filep->f_inode;
FAR struct as726x_dev_s *priv = inode->i_private;
FAR struct as726x_sensor_data_s *data =
(FAR struct as726x_sensor_data_s *)buffer;
/* Check if the user is reading the right size */
if (buflen < sizeof(FAR struct as726x_sensor_data_s))
{
snerr("ERROR: Not enough memory for reading all channels.\n");
return -ENOSYS;
}
else
{
data->v_r_value = as726x_getChannel(priv, AS726X_V_R);
data->b_s_value = as726x_getChannel(priv, AS726X_B_S);
data->g_t_value = as726x_getChannel(priv, AS726X_G_T);
data->y_u_value = as726x_getChannel(priv, AS726X_Y_U);
data->o_v_value = as726x_getChannel(priv, AS726X_O_V);
data->r_w_value = as726x_getChannel(priv, AS726X_R_W);
}
return buflen;
}
// /****************************************************************************
// * Name: as726x_write
// ****************************************************************************/
static ssize_t as726x_write(FAR struct file *filep,
FAR const char *buffer, size_t buflen)
{
return -ENOSYS;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: as726x_register
*
* Description:
* Register the AS726X character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/spectr0"
* i2c - An instance of the I2C interface to use to communicate with AS726X
* addr - The I2C address of the AS726X.
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int as726x_register(FAR const char *devpath, FAR struct i2c_master_s *i2c)
{
int ret;
/* Sanity check */
DEBUGASSERT(i2c != NULL);
/* Initialize the AS726X device structure */
FAR struct as726x_dev_s *priv =
(FAR struct as726x_dev_s *)kmm_malloc(sizeof(struct as726x_dev_s));
if (priv == NULL)
{
snerr("ERROR: Failed to allocate instance\n");
return -ENOMEM;
}
priv->i2c = i2c;
priv->addr = AS726X_I2C_ADDR;
uint8_t _sensorVersion = as726x_read8(priv, AS726x_HW_VERSION);
if (_sensorVersion != 0x3E && _sensorVersion != 0x3F) //HW version for AS7262 and AS7263
{
snerr("ID (should be 0x3E or 0x3F): 0x %d\n", ret);
}
// /* Initialize the device */
// /* Read the register value toogle and disable led */
ret = as726x_read8(priv, AS726x_LED_CONTROL);
if (ret < 0)
{
snerr("ERROR: Failed to initialize the AS726X!\n");
return ret;
}
uint8_t value = ret;
value &= ~(1 << 0); //Clear the bit
as726x_write8(priv, AS726x_LED_CONTROL, value);
//If you use Mode 2 or 3 (all the colors) then integration time is double. 140*2 = 280ms between readings.
//50 * 2.8ms = 140ms. 0 to 255 is valid.
as726x_write8(priv, AS726x_INT_T, AS726X_INTEGRATION_TIME);
ret = as726x_read8(priv, AS726x_CONTROL_SETUP);
if (ret < 0)
{
snerr("ERROR: Failed to initialize the AS726X!\n");
return ret;
}
value = ret;
value &= 0b11001111; //Clear GAIN bits
value |= (AS726X_GAIN << 4); //Set GAIN bits with user's choice
as726x_write8(priv, AS726x_CONTROL_SETUP, value);
ret = as726x_read8(priv, AS726x_CONTROL_SETUP);
if (ret < 0)
{
snerr("ERROR: Failed to initialize the AS726X!\n");
return ret;
}
value = ret;
value &= 0b11110011; //Clear BANK bits
value |= (AS726X_MEASURMENT_MODE << 2); //Set BANK bits with user's choice
as726x_write8(priv, AS726x_CONTROL_SETUP, value);
// /* Register the character driver */
ret = register_driver(devpath, &g_as726x_fops, 0666, priv);
if (ret < 0)
{
snerr("ERROR: Failed to register driver: %d\n", ret);
kmm_free(priv);
}
return ret;
}
#endif /* CONFIG_I2C && CONFIG_SENSORS_AS726X */

View File

@ -0,0 +1,163 @@
/****************************************************************************
* include/nuttx/input/as726x.h
*
* Copyright (C) 2019 Fabian Justi. All rights reserved.
* Author: Fabian Justi <Fabian.Justi@gmx.de> and
* Andreas Kurz <andreas.kurz@methodpark.de>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor 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_AS726X_H
#define __INCLUDE_NUTTX_SENSORS_AS726X_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/irq.h>
#include <nuttx/sensors/ioctl.h>
#if defined(CONFIG_SENSORS_AS726X)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define AS726X_I2C_PORTNO 1 /* On I2C1 */
/* Device I2C Address */
// #define AS726X_I2C_DATA_LSB_CMD_ADDR 0x38
// #define AS726X_I2C_DATA_MSB_ADDR 0x39
#define AS726X_I2C_ADDR 0x49 //7-bit unshifted default I2C Address
#define SENSORTYPE_AS7262 0x3E
#define SENSORTYPE_AS7263 0x3F
//Register addresses
#define AS726x_DEVICE_TYPE 0x00
#define AS726x_HW_VERSION 0x01
#define AS726x_CONTROL_SETUP 0x04
#define AS726x_INT_T 0x05
#define AS726x_DEVICE_TEMP 0x06
#define AS726x_LED_CONTROL 0x07
#define AS72XX_SLAVE_STATUS_REG 0x00
#define AS72XX_SLAVE_WRITE_REG 0x01
#define AS72XX_SLAVE_READ_REG 0x02
//The same register locations are shared between the AS7262 (V,B,G,Y,O,R) and AS7263 (R,S,T,U,V,W)
//AS7262 and AS7263 registers
#define AS726X_V_R 0x08
#define AS726X_B_S 0x0A
#define AS726X_G_T 0x0C
#define AS726X_Y_U 0x0E
#define AS726X_O_V 0x10
#define AS726X_R_W 0x12
#define AS726X_V_R_CAL 0x14
#define AS726X_B_S_CAL 0x18
#define AS726X_G_T_CAL 0x1C
#define AS726X_Y_U_CAL 0x20
#define AS726X_O_V_CAL 0x24
#define AS726X_R_W_CAL 0x28
#define AS72XX_SLAVE_TX_VALID 0x02
#define AS72XX_SLAVE_RX_VALID 0x01
#define SENSORTYPE_AS7262 0x3E
#define SENSORTYPE_AS7263 0x3F
#define AS726X_POLLING_DELAY 5000 //Amount of ms to wait between checking for virtual register changes
// #define AS726X_CMD_SD 0x01 /* Shutdown command */
// #define AS726X_CMD_RSV 0x02
// #define AS726X_CMD_IT_0_5T 0x00 /* IT1=0 : IT0=0 */
// #define AS726X_CMD_IT_1T 0x04 /* IT1=0 : IT0=1 */
// #define AS726X_CMD_IT_2T 0x08 /* IT1=1 : IT0=0 */
// #define AS726X_CMD_IT_4T 0x0c /* IT1=1 : IT0=1 */
// #define AS726X_CMD_ACK_THD 0x10 /* Acknowledge thresold:
// 0 = 102 steps
// 1 = 145 steps */
// #define AS726X_CMD_ACK 0x20 /* Acknowledge activity */
/****************************************************************************
* Public Types
****************************************************************************/
struct i2c_master_s;
struct as726x_sensor_data_s
{
uint16_t v_r_value;
uint16_t b_s_value;
uint16_t g_t_value;
uint16_t y_u_value;
uint16_t o_v_value;
uint16_t r_w_value;
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: as726x_register
*
* Description:
* Register the AS726X character device as 'devpath'
*
* Input Parameters:
* devpath - The full path to the driver to register. E.g., "/dev/spectr0"
* i2c - An instance of the I2C interface to use to communicate with
* AS726X
* addr - The I2C address of the AS726X.
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int as726x_register(FAR const char *devpath, FAR struct i2c_master_s *i2c);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* CONFIG_SENSORS_AS726X */
#endif /* __INCLUDE_NUTTX_SENSORS_AS726X_H */