diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index cfff74ff63..3eb524dc52 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -338,6 +338,34 @@ config ADXL345_REGDEBUG endif # SENSORS_ADXL345 +config SENSORS_MAX44009 + bool "Maxim MAX44009 ALS sensor" + default n + select I2C + ---help--- + Enables MAX44009 Ambient Light Sensor + +if SENSORS_MAX44009 + +config MAX44009_I2C_FREQUENCY + int "MAX44009 I2C frequency" + default 400000 + range 1 400000 + +config DEBUG_MAX44009 + bool "Enable debug support for the MAX44009" + default n + ---help--- + Enables debug support for the MAX44009 + +config MAX44009_NPOLLWAITERS + int "Number of waiters to poll" + default 1 + ---help--- + Number of waiters to poll + +endif # SENSORS_MAX44009 + config SENSORS_MAX31855 bool "Maxim MAX31855 Driver" default n diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index 42b6e6f0b8..c4cfe3af0d 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -105,6 +105,10 @@ ifeq ($(CONFIG_SENSORS_LM92),y) CSRCS += lm92.c endif +ifeq ($(CONFIG_SENSORS_MAX44009),y) + CSRCS += max44009.c +endif + ifeq ($(CONFIG_SENSORS_MB7040),y) CSRCS += mb7040.c endif diff --git a/drivers/sensors/max44009.c b/drivers/sensors/max44009.c new file mode 100644 index 0000000000..eaf6724934 --- /dev/null +++ b/drivers/sensors/max44009.c @@ -0,0 +1,957 @@ +/**************************************************************************** + * drivers/sensors/max44009.c + * + * Copyright (C) 2014-2018 Haltian Ltd. All rights reserved. + * Authors: Dmitry Nikolaev + * Juha Niskanen + * + * 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 +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_MAX44009 +# define max44009_dbg(x, ...) _info(x, ##__VA_ARGS__) +#else +# define max44009_dbg(x, ...) sninfo(x, ##__VA_ARGS__) +#endif + +#ifndef CONFIG_MAX44009_I2C_FREQUENCY +# define CONFIG_MAX44009_I2C_FREQUENCY 400000 +#endif + +/* Registers */ + +#define MAX44009_INT_STS 0x0 +#define MAX44009_INT_EN 0x01 +#define MAX44009_CONFIG 0x02 +#define MAX44009_LUX_HBYTE 0x03 +#define MAX44009_LUX_LBYTE 0x04 +#define MAX44009_UP_THRESH_BYTE 0x05 +#define MAX44009_LOW_THRESH_BYTE 0x06 +#define MAX44009_THRESH_TIMER 0x07 + +/* Other constants */ + +#define MAX44009_I2C_RETRIES 10 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct max44009_dev_s +{ + FAR struct max44009_config_s *config; + sem_t dev_sem; + FAR struct i2c_master_s *i2c; + uint8_t addr; + uint8_t cref; + bool int_pending; +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_MAX44009_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int max44009_open(FAR struct file *filep); +static int max44009_close(FAR struct file *filep); +static ssize_t max44009_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); +static ssize_t max44009_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen); +static int max44009_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int max44009_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup); +#endif + +static int max44009_read_data(FAR struct max44009_dev_s *priv, + FAR struct max44009_data_s *data); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_alsops = +{ + max44009_open, /* open */ + max44009_close, /* close */ + max44009_read, /* read */ + max44009_write, /* write */ + NULL, /* seek */ + max44009_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , max44009_poll /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int max44009_do_transfer(FAR struct max44009_dev_s *dev, + FAR struct i2c_msg_s *msgv, + size_t nmsg) +{ + int ret = -EIO; + int retries; + + for (retries = 0; retries < MAX44009_I2C_RETRIES; retries++) + { + ret = I2C_TRANSFER(dev->i2c, msgv, nmsg); + if (ret >= 0) + { + return 0; + } + else + { +#ifdef CONFIG_I2C_RESET + /* Some error. Try to reset I2C bus and keep trying. */ + + if (retries == MAX44009_I2C_RETRIES - 1) + { + break; + } + + ret = I2C_RESET(dev->i2c); + if (ret < 0) + { + max44009_dbg("I2C_RESET failed: %d\n", ret); + return ret; + } +#endif + } + } + + max44009_dbg("xfer failed: %d\n", ret); + return ret; +} + +static int max44009_write_reg8(FAR struct max44009_dev_s *dev, + FAR const uint8_t *command) +{ + struct i2c_msg_s msgv[2] = + { + { + .frequency = CONFIG_MAX44009_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = (void *)&command[0], + .length = 1 + }, + { + .frequency = CONFIG_MAX44009_I2C_FREQUENCY, + .addr = dev->addr, + .flags = I2C_M_NORESTART, + .buffer = (void *)&command[1], + .length = 1 + } + }; + + return max44009_do_transfer(dev, msgv, 2); +} + +static int max44009_read_reg8(FAR struct max44009_dev_s *dev, + FAR uint8_t *command, + FAR uint8_t *value) +{ + struct i2c_msg_s msgv[2] = + { + { + .frequency = CONFIG_MAX44009_I2C_FREQUENCY, + .addr = dev->addr, + .flags = 0, + .buffer = command, + .length = 1 + }, + { + .frequency = CONFIG_MAX44009_I2C_FREQUENCY, + .addr = dev->addr, + .flags = I2C_M_READ, + .buffer = value, + .length = 1 + } + }; + + return max44009_do_transfer(dev, msgv, 2); +} + +static int max44009_open(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct max44009_dev_s *priv; + unsigned int use_count; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max44009_dev_s *)inode->i_private; + + do + { + ret = nxsem_wait(&priv->dev_sem); + + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + DEBUGASSERT(ret == OK || ret == -EINTR); + } + while (ret == -EINTR); + + use_count = priv->cref + 1; + if (use_count == 1) + { + /* First user, do power on. */ + + ret = priv->config->set_power(priv->config, true); + if (ret < 0) + { + max44009_dbg("Cannot power on sensor: %d\n", ret); + goto out_sem; + } + + priv->config->irq_enable(priv->config, true); + priv->cref = use_count; + } + else + { + DEBUGASSERT(use_count < UINT8_MAX && use_count > priv->cref); + + priv->cref = use_count; + ret = 0; + } + + max44009_dbg("Sensor is powered on\n"); + +out_sem: + nxsem_post(&priv->dev_sem); + return ret; +} + +static int max44009_close(FAR struct file *filep) +{ + FAR struct inode *inode; + FAR struct max44009_dev_s *priv; + int use_count; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max44009_dev_s *)inode->i_private; + + do + { + ret = nxsem_wait(&priv->dev_sem); + + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + DEBUGASSERT(ret == OK || ret == -EINTR); + } + while (ret == -EINTR); + + use_count = priv->cref - 1; + if (use_count == 0) + { + priv->config->irq_enable(priv->config, false); + + /* Last user, do power off. */ + + (void)priv->config->set_power(priv->config, false); + priv->cref = use_count; + } + else + { + DEBUGASSERT(use_count > 0); + + priv->cref = use_count; + } + + max44009_dbg("CLOSED\n"); + nxsem_post(&priv->dev_sem); + return OK; +} + +static ssize_t max44009_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct inode *inode; + FAR struct max44009_dev_s *priv; + ssize_t length = 0; + int ret; + struct max44009_data_s data; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max44009_dev_s *)inode->i_private; + + do + { + ret = nxsem_wait(&priv->dev_sem); + + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + DEBUGASSERT(ret == OK || ret == -EINTR); + } + while (ret == -EINTR); + + ret = max44009_read_data(priv, &data); + if (ret < 0) + { + max44009_dbg("failed to read the sensor\n"); + } + else + { + /* This interface is mainly intended for easy debugging in nsh. */ + + length = snprintf(buffer, buflen, "%u.%03hu", data.lux, data.mlux); + if (length > buflen) + { + length = buflen; + } + } + + nxsem_post(&priv->dev_sem); + return length; +} + +static ssize_t max44009_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + ssize_t length = 0; + return length; +} + +static int max44009_set_interrupt_bit(FAR struct max44009_dev_s *priv, + bool is_activated) +{ + int ret; + uint8_t cmd[2]; + + cmd[0] = MAX44009_INT_EN; + cmd[1] = is_activated ? (1 << 0) : 0; + + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set interrupt bit\n"); + } + + return ret; +} + +static int max44009_set_manual_mode(FAR struct max44009_dev_s *priv, + bool is_manual) +{ + int ret; + uint8_t value = 0; + const uint8_t manual_bit = (1 << 6); + uint8_t cmd[2]; + + cmd[0] = MAX44009_CONFIG; + ret = max44009_read_reg8(priv, &cmd[0], &value); + if (ret < 0) + { + max44009_dbg("Cannot read config register\n"); + goto fail; + } + + if (is_manual) + { + value |= manual_bit; + } + else + { + value &= ~manual_bit; + } + + cmd[1] = value; + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set manual bit in config register\n"); + } + +fail: + return ret; +} + +static int max44009_set_continuous_mode(FAR struct max44009_dev_s *priv, + bool is_cont) +{ + int ret; + uint8_t value = 0; + const uint8_t cont_bit = (1 << 7); + uint8_t cmd[2]; + + cmd[0] = MAX44009_CONFIG; + ret = max44009_read_reg8(priv, &cmd[0], &value); + if (ret < 0) + { + max44009_dbg("Cannot read config register\n"); + goto fail; + } + + if (is_cont) + { + value |= cont_bit; + } + else + { + value &= ~cont_bit; + } + + cmd[1] = value; + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set cont bit in config register\n"); + } + +fail: + return ret; +} + +static int max44009_set_current_div_ratio(FAR struct max44009_dev_s *priv, + bool is_cdr) +{ + int ret; + uint8_t value = 0; + const uint8_t cdr_bit = (1 << 3); + uint8_t cmd[2]; + + cmd[0] = MAX44009_CONFIG; + ret = max44009_read_reg8(priv, &cmd[0], &value); + if (ret < 0) + { + max44009_dbg("Cannot read config register\n"); + goto fail; + } + + if (is_cdr) + { + value |= cdr_bit; + } + else + { + value &= ~cdr_bit; + } + + cmd[1] = value; + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set cdr bit in config register\n"); + } + +fail: + return ret; +} + +static int max44009_set_integration_time(FAR struct max44009_dev_s *priv, + enum max44009_integration_time_e + integration_time) +{ + int ret; + uint8_t value = 0; + const uint8_t tim_bits = integration_time << 0; + const uint8_t tim_mask = 0x07; + uint8_t cmd[2]; + + cmd[0] = MAX44009_CONFIG; + ret = max44009_read_reg8(priv, &cmd[0], &value); + if (ret < 0) + { + max44009_dbg("Cannot read config register\n"); + goto fail; + } + + value &= ~tim_mask; + value |= tim_bits; + + cmd[1] = value; + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set tim bits in config register\n"); + } + +fail: + return ret; +} + +static int max44009_set_threshold_timer(FAR struct max44009_dev_s *priv, + uint8_t threshold_timer) +{ + int ret; + uint8_t cmd[2]; + + cmd[0] = MAX44009_THRESH_TIMER; + cmd[1] = threshold_timer; + + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Threshold timer cannot be set\n"); + } + + return ret; +} + +static int max44009_set_threshold(FAR struct max44009_dev_s *priv, + FAR struct max44009_threshold_s *settings) +{ + int ret; + uint8_t cmd[2]; + + cmd[0] = MAX44009_UP_THRESH_BYTE; + cmd[1] = settings->upper_threshold; + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set upper threshold\n"); + goto fail; + } + + cmd[0] = MAX44009_LOW_THRESH_BYTE; + cmd[1] = settings->lower_threshold; + ret = max44009_write_reg8(priv, cmd); + if (ret < 0) + { + max44009_dbg("Cannot set lower threshold\n"); + goto fail; + } + + ret = max44009_set_threshold_timer(priv, settings->threshold_timer); + if (ret < 0) + { + max44009_dbg("Cannot set threshold timer\n"); + goto fail; + } + + ret = max44009_set_interrupt_bit(priv, true); + if (ret < 0) + { + max44009_dbg("Cannot set interrupt\n"); + goto fail; + } + +fail: + return ret; +} + +static int max44009_selftest(FAR struct max44009_dev_s *priv, + FAR struct max44009_data_s * data) +{ + int ret; + uint8_t reg_addr = MAX44009_THRESH_TIMER; + uint8_t value = 0; + + ret = max44009_set_threshold_timer(priv, data->test_value); + if (ret < 0) + { + max44009_dbg("Cannot write test-value\n"); + goto fail; + } + + ret = max44009_read_reg8(priv, ®_addr, &value); + if (ret < 0) + { + max44009_dbg("Cannot read written value\n"); + goto fail; + } + + if (value != data->test_value) + { + max44009_dbg("Test failed\n"); + ret = -EIO; + } + +fail: + return ret; +} + +static int max44009_init_device(FAR struct max44009_dev_s *priv, + FAR struct max44009_init_s * settings) +{ + int ret; + + ret = max44009_set_manual_mode(priv, settings->is_manual); + if (ret < 0) + { + max44009_dbg("Cannot init manual mode\n"); + goto fail; + } + + ret = max44009_set_continuous_mode(priv, settings->is_cont); + if (ret < 0) + { + max44009_dbg("Cannot init cont mode\n"); + goto fail; + } + + if (settings->is_manual) + { + ret = max44009_set_current_div_ratio(priv, settings->is_cdr); + if (ret < 0) + { + max44009_dbg("Cannot init cdr mode\n"); + goto fail; + } + + ret = max44009_set_integration_time(priv, settings->integr_time); + if (ret < 0) + { + max44009_dbg("Cannot init tim mode\n"); + goto fail; + } + } + +fail: + return ret; +} + +static int max44009_read_data(FAR struct max44009_dev_s *priv, + FAR struct max44009_data_s *data) +{ + int ret; + uint8_t lvalue; + uint8_t hvalue; + uint8_t reg_addr; + uint32_t val; + + reg_addr = MAX44009_INT_STS; + ret = max44009_read_reg8(priv, ®_addr, &hvalue); + if (ret < 0) + { + max44009_dbg("Cannot read interrupt status register\n"); + } + + reg_addr = MAX44009_LUX_HBYTE; + ret = max44009_read_reg8(priv, ®_addr, &hvalue); + if (ret < 0) + { + max44009_dbg("Cannot read high bits from lux register\n"); + return ret; + } + + /* LUX HBYTE has (starting with MSB): E3.E2.E1.E0.M7.M6.M5.M4 + * LUX LBYTE has : --.--.--.--.M3.M2.M1.M0 + * + * E[3..0] = Exponent, M[7..0]: Mantissa. + * + * Lux can be calculated as (full resolution): (M[7..0] << E[3..0]) * 0.045. + * + * Lux can also be calculated using only HBYTE: + * (M[7..4] << E[3..0]) * 0.72 + * == (M[7..4] << E[3..0]) * 2^4 * 0.045 + * == (M[7..4] << E[3..0]) * (1 << 4) * 0.045 + * == (M[7..4] << (E[3..0] + 4)) * 0.045 + */ + + reg_addr = MAX44009_LUX_LBYTE; + ret = max44009_read_reg8(priv, ®_addr, &lvalue); + if (ret < 0) + { + max44009_dbg("Cannot read low bits from lux register\n"); + return ret; + } + + /* Merge HBYTE and LBYTE to 16-bit integer: + * --.--.--.--.E3.E2.E1.E0.M7.M6.M5.M4.M3.M2.M1.M0 */ + + data->raw_value = (hvalue << 4) | (lvalue & 0xf); + + /* Add raw value to entropy pool. */ + + add_sensor_randomness(data->raw_value); + + /* Convert raw value to lux and millilux. */ + + val = data->raw_value & 0xff; + val = val << ((data->raw_value & 0x0f00) >> 8); + + /* lux is the raw output multiplied by 0.045. */ + + data->lux = (val * 45) / 1000; + data->mlux = (val * 45) % 1000; + + return ret; +} + +static int max44009_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct max44009_dev_s *priv; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max44009_dev_s *)inode->i_private; + + do + { + ret = nxsem_wait(&priv->dev_sem); + + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + DEBUGASSERT(ret == OK || ret == -EINTR); + } + while (ret == -EINTR); + + switch (cmd) + { + case SNIOC_INIT: + ret = max44009_init_device(priv, (FAR struct max44009_init_s *)arg); + break; + + case SNIOC_THRESHOLD: + ret = max44009_set_threshold(priv, + (FAR struct max44009_threshold_s *)arg); + break; + + case SNIOC_READ_RAW_DATA: + case SNIOC_READ_CONVERT_DATA: + ret = max44009_read_data(priv, (FAR struct max44009_data_s *)arg); + break; + + case SNIOC_START_SELFTEST: + ret = max44009_selftest(priv, (FAR struct max44009_data_s *)arg); + break; + + default: + ret = -ENOTTY; + break; + } + + nxsem_post(&priv->dev_sem); + return ret; +} + +#ifndef CONFIG_DISABLE_POLL +static void max44009_notify(FAR struct max44009_dev_s *priv) +{ + DEBUGASSERT(priv != NULL); + + int i; + + /* If there are threads waiting on poll() for data to become available, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the + * data, then some make end up blocking after all. + */ + + for (i = 0; i < CONFIG_MAX44009_NPOLLWAITERS; i++) + { + FAR struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + max44009_dbg("Report events: %02x\n", fds->revents); + nxsem_post(fds->sem); + priv->int_pending = false; + } + } +} + +static int max44009_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct max44009_dev_s *priv; + int ret; + int i; + + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max44009_dev_s *)inode->i_private; + + do + { + ret = nxsem_wait(&priv->dev_sem); + + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + DEBUGASSERT(ret == OK || ret == -EINTR); + } + while (ret == -EINTR); + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->events & POLLIN) == 0) + { + ret = -EDEADLK; + goto out; + } + + /* This is a request to set up the poll. Find an available slot for the + * poll structure reference */ + + for (i = 0; i < CONFIG_MAX44009_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_MAX44009_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto out; + } + if (priv->int_pending) + { + max44009_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } +out: + nxsem_post(&priv->dev_sem); + return ret; +} +#endif /* !CONFIG_DISABLE_POLL */ + +static int max44009_int_handler(int irq, FAR void *context, FAR void *arg) +{ + FAR struct max44009_dev_s *priv = (FAR struct max44009_dev_s *)arg; + irqstate_t flags; + + DEBUGASSERT(priv != NULL); + + flags = enter_critical_section(); + priv->int_pending = true; + leave_critical_section(flags); +#ifndef CONFIG_DISABLE_POLL + max44009_notify(priv); +#endif + max44009_dbg("MAX44009 interrupt\n"); + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int max44009_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR struct max44009_config_s *config) +{ + struct max44009_dev_s *priv; + int ret; + + priv = kmm_zalloc(sizeof(struct max44009_dev_s)); + if (!priv) + { + max44009_dbg("Memory cannot be allocated for ALS sensor\n"); + return -ENOMEM; + } + + priv->addr = addr; + priv->i2c = i2c; + priv->config = config; + nxsem_init(&priv->dev_sem, 0, 1); + + ret = register_driver(devpath, &g_alsops, 0666, priv); + max44009_dbg("Registered with %d\n", ret); + if (ret < 0) + { + kmm_free(priv); + max44009_dbg("Error occurred during the driver registering\n"); + return ret; + } + + priv->config->irq_attach(priv->config, max44009_int_handler, priv); + priv->config->irq_enable(priv->config, false); + return ret; +} diff --git a/include/nuttx/sensors/ioctl.h b/include/nuttx/sensors/ioctl.h index 62d33b9f52..3f6add61d0 100644 --- a/include/nuttx/sensors/ioctl.h +++ b/include/nuttx/sensors/ioctl.h @@ -118,10 +118,10 @@ /* IOCTL commands to the HTS221 & LPS25H */ #define SNIOC_CFGR _SNIOC(0x002a) +#define SNIOC_GET_DEV_ID _SNIOC(0x002b) /* IOCTL commands unique to the HTS221 */ -#define SNIOC_GET_DEV_ID _SNIOC(0x002b) #define SNIOC_START_CONVERSION _SNIOC(0x002c) #define SNIOC_CHECK_STATUS_REG _SNIOC(0x002d) #define SNIOC_READ_RAW_DATA _SNIOC(0x002e) @@ -130,19 +130,23 @@ /* IOCTL commands unique to the LPS25H */ -#define SNIOC_GET_DEV_ID _SNIOC(0x0031) -#define SNIOC_TEMPERATURE_OUT _SNIOC(0x0032) -#define SNIOC_PRESSURE_OUT _SNIOC(0x0033) -#define SNIOC_SENSOR_OFF _SNIOC(0x0034) +#define SNIOC_TEMPERATURE_OUT _SNIOC(0x0031) +#define SNIOC_PRESSURE_OUT _SNIOC(0x0032) +#define SNIOC_SENSOR_OFF _SNIOC(0x0033) /* IOCTL commands unique to the LIS2DH */ -#define SNIOC_WRITESETUP _SNIOC(0x0035) /* Arg: uint8_t value */ -#define SNIOC_WRITE_INT1THRESHOLD _SNIOC(0x0036) /* Arg: uint8_t value */ -#define SNIOC_WRITE_INT2THRESHOLD _SNIOC(0x0037) /* Arg: uint8_t value */ -#define SNIOC_RESET_HPFILTER _SNIOC(0x0038) /* Arg: uint8_t value */ -#define SNIOC_START_SELFTEST _SNIOC(0x0039) /* Arg: uint8_t value */ -#define SNIOC_WHO_AM_I _SNIOC(0x003a) -#define SNIOC_READ_TEMP _SNIOC(0x003b) /* Arg: int16_t value */ +#define SNIOC_WRITESETUP _SNIOC(0x0034) /* Arg: uint8_t value */ +#define SNIOC_WRITE_INT1THRESHOLD _SNIOC(0x0035) /* Arg: uint8_t value */ +#define SNIOC_WRITE_INT2THRESHOLD _SNIOC(0x0036) /* Arg: uint8_t value */ +#define SNIOC_RESET_HPFILTER _SNIOC(0x0037) /* Arg: uint8_t value */ +#define SNIOC_START_SELFTEST _SNIOC(0x0038) /* Arg: uint8_t value */ +#define SNIOC_WHO_AM_I _SNIOC(0x0039) +#define SNIOC_READ_TEMP _SNIOC(0x003a) /* Arg: int16_t value */ + +/* IOCTL commands unique to the MAX44009 */ + +#define SNIOC_INIT _SNIOC(0x003b) +#define SNIOC_THRESHOLD _SNIOC(0x003c) #endif /* __INCLUDE_NUTTX_SENSORS_IOCTL_H */ diff --git a/include/nuttx/sensors/max44009.h b/include/nuttx/sensors/max44009.h new file mode 100644 index 0000000000..9cf1a2723b --- /dev/null +++ b/include/nuttx/sensors/max44009.h @@ -0,0 +1,118 @@ +/**************************************************************************** + * include/nuttx/sensors/max44009.h + * + * Copyright (C) 2014-2018 Haltian Ltd. All rights reserved. + * Authors: Dmitry Nikolaev + * Juha Niskanen + * + * 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_MAX44009 +#define __INCLUDE_NUTTX_SENSORS_MAX44009 + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct i2c_master_s; + +/* Integration time, ms */ + +enum max44009_integration_time_e +{ + MAX44009_INTEGR_TIME_800 = 0x0, /* Preferred mode for boosting + * low-light sensitivity */ + MAX44009_INTEGR_TIME_400, + MAX44009_INTEGR_TIME_200, + MAX44009_INTEGR_TIME_100, /* Preferred mode for high-brightness + * applications */ + MAX44009_INTEGR_TIME_50, /* Manual mode only */ + MAX44009_INTEGR_TIME_25, /* Manual mode only */ + MAX44009_INTEGR_TIME_12_5, /* Manual mode only */ + MAX44009_INTEGR_TIME_6_25 /* Manual mode only */ +}; + +/* Board configuration data structure */ + +struct max44009_config_s +{ + CODE int (*irq_attach)(FAR struct max44009_config_s * state, xcpt_t isr, FAR void *arg); + CODE void (*irq_enable)(FAR const struct max44009_config_s * state, bool enable); + CODE int (*set_power)(FAR const struct max44009_config_s * state, bool on); +}; + +/* Configuration structure for MAX44009 */ + +struct max44009_init_s +{ + bool is_cont; /* Needs more power, if it's in continuous + * mode. This one is useful in test-mode for + * instance */ + bool is_manual; /* Timer's settings must be specified manually */ + bool is_cdr; /* Current division ratio: false - All of the + * photodiode current goes to the ADC, true - + * 1/8 (must be used in high-brightness + * situations) */ + enum max44009_integration_time_e integr_time; /* Integration time */ +}; + +struct max44009_threshold_s +{ + uint8_t upper_threshold; /* Upper threshold high-byte */ + uint8_t lower_threshold; /* Lower threshold high-byte */ + uint8_t threshold_timer; /* 0 - interrupt will be triggered as soon as + * the light level exceeds either threshold */ +} ; + +/* Data transfer structure */ + +struct max44009_data_s +{ + uint32_t lux; /* Converted lux value */ + uint16_t mlux; /* Converted millilux (decimals for lux) */ + uint16_t raw_value; /* Raw unconverted value */ + uint8_t test_value; /* For self-test only */ +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +int max44009_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR struct max44009_config_s *config); + +#endif /* __INCLUDE_NUTTX_SENSORS_MAX44009 */