diff --git a/crypto/random_pool.c b/crypto/random_pool.c index fed59bd727..7fd761be00 100644 --- a/crypto/random_pool.c +++ b/crypto/random_pool.c @@ -367,7 +367,7 @@ static void rng_buf_internal(FAR void *bytes, size_t nbytes) static void rng_init(void) { - crypinfo("Initializing RNG\n"); + cryptinfo("Initializing RNG\n"); memset(&g_rng, 0, sizeof(struct rng_s)); sem_init(&g_rng.rd_sem, 0, 1); diff --git a/drivers/Kconfig b/drivers/Kconfig index 511d63c5f6..d7bc265374 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -552,6 +552,16 @@ if USBHOST source drivers/usbhost/Kconfig endif # USBHOST +menuconfig USBMISC + bool "USB Miscellaneous drivers" + default n + ---help--- + USB Miscellaneous drivers. + +if USBMISC +source drivers/usbmisc/Kconfig +endif # USBMISC + config HAVE_USBTRACE bool default n diff --git a/drivers/Makefile b/drivers/Makefile index 94f027afbb..5946cc123a 100644 --- a/drivers/Makefile +++ b/drivers/Makefile @@ -72,6 +72,7 @@ include syslog$(DELIM)Make.defs include timers$(DELIM)Make.defs include usbdev$(DELIM)Make.defs include usbhost$(DELIM)Make.defs +include usbmisc$(DELIM)Make.defs include usbmonitor$(DELIM)Make.defs include video$(DELIM)Make.defs include wireless$(DELIM)Make.defs diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index 5871c18b81..969f5e1010 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -33,11 +33,11 @@ config BMP180 Enable driver support for the Bosch BMP180 barometer sensor. config HTS221 - bool "ST HTS221 humidity sensor" + bool "STMicro HTS221 humidity sensor" default n select I2C ---help--- - Enable driver support for the ST HTS221 humidity sensor. + Enable driver support for the STMicro HTS221 humidity sensor. if HTS221 @@ -56,11 +56,11 @@ config HTS221_NPOLLWAITERS endif # HTS221 config SENSORS_L3GD20 - bool "ST L3GD20 Gyroscope Sensor support" + bool "STMicro L3GD20 Gyroscope Sensor support" default n select SPI ---help--- - Enable driver support for the ST L3GD20 gyroscope sensor. + Enable driver support for the STMicro L3GD20 gyroscope sensor. config SENSOR_KXTJ9 bool "Kionix KXTJ9 Accelerometer support" @@ -83,7 +83,7 @@ config LIS3DSH Enable driver support for the STMicro LIS3DSH 3-Axis acclerometer. config LIS331DL - bool "ST LIS331DL device support" + bool "STMicro LIS331DL device support" default n select I2C @@ -106,6 +106,23 @@ config LSM9DS1_I2C_FREQUENCY range 1 400000 depends on SN_LSM9DS1 +config LPS25H + bool "STMicro LPS25H pressure sensor" + default n + select I2C + ---help--- + Enable driver support for the STMicro LPS25H barometer sensor. + +if LPS25H + +config DEBUG_LPS25H + bool "Debug support for the LPS25H" + default n + ---help--- + Enables debug features for the LPS25H + +endif # LPS25H + config MB7040 bool "MaxBotix MB7040 Sonar support" default n @@ -209,7 +226,7 @@ endif # SENSORS_ADXL345 config MAX31855 bool "Maxim MAX31855 Driver" default n - select SPI + select SPI ---help--- Enables support for the MAX31855 driver @@ -229,7 +246,7 @@ config LIS3MDL default n select SPI ---help--- - Enable driver support for the ST LIS3MDL 3-axis magnetometer. + Enable driver support for the STMicro LIS3MDL 3-axis magnetometer. config LM75 bool "STMicro LM-75 Temperature Sensor support" diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index d0bb9fa650..b676c4aa8e 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # drivers/sensors/Make.defs # -# Copyright (C) 2011-2012, 2015-2016 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012, 2015-2017 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -65,6 +65,10 @@ ifeq ($(CONFIG_SN_LSM9DS1),y) CSRCS += lsm9ds1.c endif +ifeq ($(CONFIG_LPS25H),y) + CSRCS += lps25h.c +endif + ifeq ($(CONFIG_ADXL345_I2C),y) CSRCS += adxl345_i2c.c endif diff --git a/drivers/sensors/hts221.c b/drivers/sensors/hts221.c index 4dc9c0d2dd..59c5790ad5 100644 --- a/drivers/sensors/hts221.c +++ b/drivers/sensors/hts221.c @@ -174,13 +174,11 @@ static const struct file_operations g_humidityops = #endif }; -static struct hts221_dev_s *g_humid_data; - /**************************************************************************** * Private Functions ****************************************************************************/ -static int hts221_do_transfer(FAR struct hts221_dev_s *dev, +static int hts221_do_transfer(FAR struct hts221_dev_s *priv, FAR struct i2c_msg_s *msgv, size_t nmsg) { @@ -189,7 +187,7 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *dev, for (retries = 0; retries < HTS221_I2C_RETRIES; retries++) { - ret = I2C_TRANSFER(dev->i2c, msgv, nmsg); + ret = I2C_TRANSFER(priv->i2c, msgv, nmsg); if (ret >= 0) { return 0; @@ -203,7 +201,7 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *dev, break; } - ret = up_i2creset(dev->i2c); + ret = up_i2creset(priv->i2c); if (ret < 0) { hts221_dbg("up_i2creset failed: %d\n", ret); @@ -217,51 +215,51 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *dev, return ret; } -static int32_t hts221_write_reg8(FAR struct hts221_dev_s *dev, +static int32_t hts221_write_reg8(FAR struct hts221_dev_s *priv, const uint8_t *command) { struct i2c_msg_s msgv[2] = { { - .addr = dev->addr, + .addr = priv->addr, .flags = 0, .buffer = (FAR void *)&command[0], .length = 1 }, { - .addr = dev->addr, + .addr = priv->addr, .flags = I2C_M_NORESTART, .buffer = (FAR void *)&command[1], .length = 1 } }; - return hts221_do_transfer(dev, msgv, 2); + return hts221_do_transfer(priv, msgv, 2); } -static int hts221_read_reg(FAR struct hts221_dev_s *dev, +static int hts221_read_reg(FAR struct hts221_dev_s *priv, FAR const uint8_t *command, FAR uint8_t *value) { struct i2c_msg_s msgv[2] = { { - .addr = dev->addr, + .addr = priv->addr, .flags = 0, .buffer = (FAR void *)command, .length = 1 }, { - .addr = dev->addr, + .addr = priv->addr, .flags = I2C_M_READ, .buffer = value, .length = 1 } }; - return hts221_do_transfer(dev, msgv, 2); + return hts221_do_transfer(priv, msgv, 2); } -static int hts221_get_id(FAR struct hts221_dev_s *priv, uint8_t * value) +static int hts221_get_id(FAR struct hts221_dev_s *priv, uint8_t *value) { int ret = OK; uint8_t cmd = HTS221_WHO_AM_I; @@ -362,7 +360,7 @@ static int hts221_config_ctrl_reg2(FAR struct hts221_dev_s *priv, } static int hts221_config_ctrl_reg1(FAR struct hts221_dev_s *priv, - FAR hts221_settings_t * settings) + FAR hts221_settings_t *settings) { int ret = OK; uint8_t regval = 0; @@ -420,7 +418,7 @@ static int hts221_power_on_off(FAR struct hts221_dev_s *priv, bool on) } static int hts221_config(FAR struct hts221_dev_s *priv, - FAR hts221_settings_t * cfgr) + FAR hts221_settings_t *cfgr) { int ret = OK; @@ -477,7 +475,7 @@ static int hts221_start_conversion(FAR struct hts221_dev_s *priv) } static int hts221_check_status(FAR struct hts221_dev_s *priv, - FAR hts221_status_t * status) + FAR hts221_status_t *status) { int ret = OK; uint8_t addr = HTS221_STATUS_REG; @@ -498,7 +496,7 @@ static int hts221_check_status(FAR struct hts221_dev_s *priv, } static int hts221_read_raw_data(FAR struct hts221_dev_s *priv, - FAR hts221_raw_data_t * data) + FAR hts221_raw_data_t *data) { int ret = OK; uint8_t addr_humid_low = HTS221_HUM_OUT_L; @@ -1069,13 +1067,14 @@ out: static int hts221_int_handler(int irq, FAR void *context, FAR void *arg) { - if (!g_humid_data) - return OK; + FAR struct hts221_dev_s *priv = (FAR struct hts221_dev_s *)arg; - g_humid_data->int_pending = true; + DEBUGASSERT(priv != NULL); + + priv->int_pending = true; hts221_dbg("Hts221 interrupt\n"); #ifndef CONFIG_DISABLE_POLL - hts221_notify(g_humid_data); + hts221_notify(priv); #endif return OK; @@ -1095,7 +1094,6 @@ int hts221_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, return -ENOMEM; } - g_humid_data = priv; priv->addr = addr; priv->i2c = i2c; priv->config = config; @@ -1125,7 +1123,7 @@ int hts221_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, priv->config->irq_clear(priv->config); } - priv->config->irq_attach(priv->config, hts221_int_handler); + priv->config->irq_attach(priv->config, hts221_int_handler, priv); priv->config->irq_enable(priv->config, false); return OK; } diff --git a/drivers/sensors/lps25h.c b/drivers/sensors/lps25h.c new file mode 100644 index 0000000000..3ebba98285 --- /dev/null +++ b/drivers/sensors/lps25h.c @@ -0,0 +1,793 @@ +/**************************************************************************** + * drivers/sensors/lps25h.c + * + * Copyright (C) 2014-2017 Haltian Ltd. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor 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 + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_LPS25H +# define lps25h_dbg(x, ...) _info(x, ##__VA_ARGS__) +#else +# define lps25h_dbg(x, ...) sninfo(x, ##__VA_ARGS__) +#endif + +#define LPS25H_PRESSURE_INTERNAL_DIVIDER 4096 + +/* 'AN4450 - Hardware and software guidelines for use of LPS25H pressure + * sensors' - '6.2 One-shot mode conversion time estimation' gives estimates + * for conversion times: + * + * Typical conversion time ≈ 62*(Pavg+Tavg) + 975 μs + * ex: Tavg = 64; Pavg = 512; Typ. conversation time ≈ 36.7 ms (compatible with + * ODT=25 Hz) + * ex: Tavg = 32; Pavg = 128; Typ. conversation time ≈ 10.9 ms + * The formula is accurate within +/- 3% at room temperature + * + * Set timeout to 2 * max.conversation time (2*36.7*1.03 = 76 ms). + */ + +#define LPS25H_RETRY_TIMEOUT_MSECS 76 +#define LPS25H_MAX_RETRIES 5 + +#define LPS25H_I2C_RETRIES 10 + +/* Registers */ + +#define LPS25H_REF_P_XL 0x08 +#define LPS25H_REF_P_L 0x09 +#define LPS25H_REF_P_H 0x0a +#define LPS25H_WHO_AM_I 0x0f +#define LPS25H_RES_CONF 0x10 +#define LPS25H_CTRL_REG1 0x20 +#define LPS25H_CTRL_REG2 0x21 +#define LPS25H_CTRL_REG3 0x22 +#define LPS25H_CTRL_REG4 0x23 +#define LPS25H_INT_CFG 0x24 +#define LPS25H_INT_SOURCE 0x25 +#define LPS25H_STATUS_REG 0x27 +#define LPS25H_PRESS_POUT_XL 0x28 +#define LPS25H_PRESS_OUT_L 0x29 +#define LPS25H_PRESS_OUT_H 0x2a +#define LPS25H_TEMP_OUT_L 0x2b +#define LPS25H_TEMP_OUT_H 0x2c +#define LPS25H_FIFO_CTRL 0x2e +#define LPS25H_FIFO_STATUS 0x2f +#define LPS25H_THS_P_L 0x30 +#define LPS25H_THS_P_H 0x31 +#define LPS25H_RPDS_L 0x39 +#define LPS25H_RPDS_H 0x3a + +/* Bits in registers */ + +#define LPS25H_AUTO_ZERO (1 << 2) +#define LPS25H_BDU (1 << 2) +#define LPS25H_DIFF_EN (1 << 3) +#define LPS25H_FIFO_EN (1 << 6) +#define LPS25H_WTM_EN (1 << 5) +#define LPS25H_FIFO_MEAN_DEC (1 << 4) +#define LPS25H_PD (1 << 7) +#define LPS25H_ONE_SHOT (1 << 0) +#define LPS25H_INT_H_L (1 << 7) +#define LPS25H_PP_OD (1 << 6) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct lps25h_dev_s +{ + struct i2c_master_s *i2c; + uint8_t addr; + bool irqenabled; + volatile bool int_pending; + sem_t devsem; + sem_t waitsem; + lps25h_config_t *config; +}; + +enum LPS25H_RES_CONF_AVG_PRES +{ + PRES_AVG_8 = 0, + PRES_AVG_32, + PRES_AVG_128, + PRES_AVG_512 +}; + +enum LPS25H_RES_CONF_AVG_TEMP +{ + TEMP_AVG_8 = 0, + TEMP_AVG_16, + TEMP_AVG_32, + TEMP_AVG_64 +}; + +enum LPS25H_CTRL_REG1_ODR +{ + CTRL_REG1_ODR_ONE_SHOT = 0, + CTRL_REG1_ODR_1Hz, + CTRL_REG1_ODR_7Hz, + CTRL_REG1_ODR_12_5Hz, + CTRL_REG1_ODR_25Hz +}; + +enum LPS25H_CTRL_REG4_P1 +{ + P1_DRDY = 0x1, + P1_OVERRUN = 0x02, + P1_WTM = 0x04, + P1_EMPTY = 0x08 +}; + +enum LPS25H_FIFO_CTRL_MODE +{ + BYPASS_MODE = 0x0, + FIFO_STOP_WHEN_FULL, + STREAM_NEWEST_IN_FIFO, + STREAM_DEASSERTED, + BYPASS_DEASSERTED_STREAM, + FIFO_MEAN = 0x06, + BYPASS_DEASSERTED_FIFO +}; + +enum LPS25H_FIFO_CTRL_WTM +{ + SAMPLE_2 = 0x01, + SAMPLE_4 = 0x03, + SAMPLE_8 = 0x07, + SAMPLE_16 = 0x0f, + SAMPLE_32 = 0x1f +}; + +enum LPS25H_INT_CFG_OP +{ + PH_E = 0x1, + PL_E = 0x2, + LIR = 0x4 +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +static int lps25h_open(FAR struct file *filep); +static int lps25h_close(FAR struct file *filep); +static ssize_t lps25h_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); +static ssize_t lps25h_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen); +static int lps25h_ioctl(FAR struct file *filep, int cmd, unsigned long arg); + +static int lps25h_configure_dev(FAR struct lps25h_dev_s *dev); +static int lps25h_read_pressure(FAR struct lps25h_dev_s *dev, + FAR lps25h_pressure_data_t *pres); +static int lps25h_read_temper(FAR struct lps25h_dev_s *dev, + FAR lps25h_temper_data_t *temper); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_lps25hops = +{ + lps25h_open, /* open */ + lps25h_close, /* close */ + lps25h_read, /* read */ + lps25h_write, /* write */ + NULL, /* seek */ + lps25h_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , NULL /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ + #endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int lps25h_do_transfer(FAR struct lps25h_dev_s *dev, + FAR struct i2c_msg_s *msgv, + size_t nmsg) +{ + int ret = -EIO; + int retries; + + for (retries = 0; retries < LPS25H_I2C_RETRIES; retries++) + { + ret = I2C_TRANSFER(dev->i2c, msgv, nmsg); + if (ret >= 0) + { + return 0; + } + else + { + /* Some error. Try to reset I2C bus and keep trying. */ +#ifdef CONFIG_I2C_RESET + if (retries == LPS25H_I2C_RETRIES - 1) + { + break; + } + + ret = up_i2creset(dev->i2c); + if (ret < 0) + { + lps25h_dbg("up_i2creset failed: %d\n", ret); + return ret; + } +#endif + } + } + + lps25h_dbg("xfer failed: %d\n", ret); + return ret; +} + +static int lps25h_write_reg8(struct lps25h_dev_s *dev, uint8_t reg_addr, + const uint8_t value) +{ + struct i2c_msg_s msgv[2] = + { + { + .addr = dev->addr, + .flags = 0, + .buffer = ®_addr, + .length = 1 + }, + { + .addr = dev->addr, + .flags = I2C_M_NORESTART, + .buffer = (void *)&value, + .length = 1 + } + }; + + return lps25h_do_transfer(dev, msgv, 2); +} + +static int lps25h_read_reg8(FAR struct lps25h_dev_s *dev, + FAR uint8_t *reg_addr, + FAR uint8_t *value) +{ + struct i2c_msg_s msgv[2] = + { + { + .addr = dev->addr, + .flags = 0, + .buffer = reg_addr, + .length = 1 + }, + { + .addr = dev->addr, + .flags = I2C_M_READ, + .buffer = value, + .length = 1 + } + }; + + return lps25h_do_transfer(dev, msgv, 2); +} + +static int lps25h_power_on_off(FAR struct lps25h_dev_s *dev, bool on) +{ + int ret; + uint8_t value; + + value = on ? LPS25H_PD : 0; + ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG1, value); + return ret; +} + +static int lps25h_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lps25h_dev_s *dev = inode->i_private; + uint8_t value = 0; + uint8_t addr = LPS25H_WHO_AM_I; + int32_t ret; + + while (sem_wait(&dev->devsem) != 0) + { + assert(errno == EINTR); + } + + dev->config->set_power(dev->config, true); + ret = lps25h_read_reg8(dev, &addr, &value); + if (ret < 0) + { + lps25h_dbg("Cannot read device's ID\n"); + dev->config->set_power(dev->config, false); + goto out; + } + + lps25h_dbg("WHO_AM_I: 0x%2x\n", value); + + dev->config->irq_enable(dev->config, true); + dev->irqenabled = true; + +out: + sem_post(&dev->devsem); + return ret; +} + +static int lps25h_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lps25h_dev_s *dev = inode->i_private; + int ret; + + while (sem_wait(&dev->devsem) != 0) + { + assert(errno == EINTR); + } + + dev->config->irq_enable(dev->config, false); + dev->irqenabled = false; + ret = lps25h_power_on_off(dev, false); + dev->config->set_power(dev->config, false); + lps25h_dbg("CLOSED\n"); + + sem_post(&dev->devsem); + return ret; +} + +static ssize_t lps25h_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lps25h_dev_s *dev = inode->i_private; + int ret; + ssize_t length = 0; + lps25h_pressure_data_t data; + + while (sem_wait(&dev->devsem) != 0) + { + assert(errno == EINTR); + } + + ret = lps25h_configure_dev(dev); + if (ret < 0) + { + lps25h_dbg("cannot configure sensor: %d\n", ret); + goto out; + } + + ret = lps25h_read_pressure(dev, &data); + if (ret < 0) + { + lps25h_dbg("cannot read data: %d\n", ret); + } + else + { + /* This interface is mainly intended for easy debugging in nsh. */ + + length = snprintf(buffer, buflen, "%u\n", data.pressure_Pa); + if (length > buflen) + { + length = buflen; + } + } + +out: + sem_post(&dev->devsem); + return length; +} + +static ssize_t lps25h_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + ssize_t length = 0; + + return length; +} + +static void lps25h_notify(FAR struct lps25h_dev_s *dev) +{ + DEBUGASSERT(dev != NULL); + + dev->int_pending = true; + sem_post(&dev->waitsem); +} + +static int lps25h_int_handler(int irq, FAR void *context, FAR void *arg) +{ + FAR struct lps25h_dev_s *dev = (FAR struct lps25h_dev_s *)arg; + + DEBUGASSERT(dev != NULL); + + lps25h_notify(dev); + lps25h_dbg("lps25h interrupt\n"); + return OK; +} + +static int lps25h_configure_dev(FAR struct lps25h_dev_s *dev) +{ + int ret = 0; + + ret = lps25h_power_on_off(dev, false); + if (ret < 0) + { + return ret; + } + + /* Enable FIFO */ + + ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG2, LPS25H_FIFO_EN); + if (ret < 0) + { + return ret; + } + + ret = lps25h_write_reg8(dev, LPS25H_FIFO_CTRL, (BYPASS_MODE << 5)); + if (ret < 0) + { + return ret; + } + + ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG4, P1_DRDY); + if (ret < 0) + { + return ret; + } + + /* Write CTRL_REG1 to turn device on */ + + ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG1, + LPS25H_PD | (CTRL_REG1_ODR_1Hz << 4)); + + return ret; +} + +static int lps25h_one_shot(FAR struct lps25h_dev_s *dev) +{ + int ret = ERROR; + int retries; + struct timespec abstime; + irqstate_t flags; + + if (!dev->irqenabled) + { + lps25h_dbg("IRQ disabled!\n"); + } + + /* Retry one-shot measurement multiple times. */ + + for (retries = 0; retries < LPS25H_MAX_RETRIES; retries++) + { + /* Power off so we start from a known state. */ + + ret = lps25h_power_on_off(dev, false); + if (ret < 0) + { + return ret; + } + + /* Initiate a one shot mode measurement */ + + ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG2, LPS25H_ONE_SHOT); + if (ret < 0) + { + return ret; + } + + /* Power on to start measurement. */ + + ret = lps25h_power_on_off(dev, true); + if (ret < 0) + { + return ret; + } + + (void)clock_gettime(CLOCK_REALTIME, &abstime); + abstime.tv_sec += (LPS25H_RETRY_TIMEOUT_MSECS / 1000); + abstime.tv_nsec += (LPS25H_RETRY_TIMEOUT_MSECS % 1000) * 1000 * 1000; + while (abstime.tv_nsec >= (1000 * 1000 * 1000)) + { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } + + while ((ret = sem_timedwait(&dev->waitsem, &abstime)) != 0) + { + int err = errno; + if (err == EINTR) + { + continue; + } + else if (err == ETIMEDOUT) + { + uint8_t reg = LPS25H_CTRL_REG2; + uint8_t value; + + /* In 'AN4450 - Hardware and software guidelines for use of + * LPS25H pressure sensors' - '4.3 One-shot mode measurement + * sequence', one-shot mode example is given where interrupt line + * is not used, but CTRL_REG2 is polled until ONE_SHOT bit is + * unset (as it is self-clearing). Check ONE_SHOT bit status here + * to see if we just missed interrupt. + */ + + ret = lps25h_read_reg8(dev, ®, &value); + if (ret < 0) + { + break; + } + + if ((value & LPS25H_ONE_SHOT) == 0) + { + /* One-shot completed. */ + + ret = OK; + break; + } + } + else + { + /* Some unknown mystery error */ + + DEBUGASSERT(false); + return -err; + } + } + + if (ret == OK) + { + break; + } + + lps25h_dbg("Retrying one-shot measurement: retries=%d\n", retries); + } + + if (ret != OK) + { + return -ETIMEDOUT; + } + + flags = enter_critical_section(); + dev->int_pending = false; + leave_critical_section(flags); + + return ret; +} + +static int lps25h_read_pressure(FAR struct lps25h_dev_s *dev, + FAR lps25h_pressure_data_t *pres) +{ + int ret; + uint8_t pres_addr_h = LPS25H_PRESS_OUT_H; + uint8_t pres_addr_l = LPS25H_PRESS_OUT_L; + uint8_t pres_addr_xl = LPS25H_PRESS_POUT_XL; + uint8_t pres_value_h = 0; + uint8_t pres_value_l = 0; + uint8_t pres_value_xl = 0; + int32_t pres_res = 0; + + ret = lps25h_one_shot(dev); + if (ret < 0) + { + return ret; + } + + ret = lps25h_read_reg8(dev, &pres_addr_h, &pres_value_h); + if (ret < 0) + { + return ret; + } + + ret = lps25h_read_reg8(dev, &pres_addr_l, &pres_value_l); + if (ret < 0) + { + return ret; + } + + ret = lps25h_read_reg8(dev, &pres_addr_xl, &pres_value_xl); + if (ret < 0) + { + return ret; + } + + pres_res = ((int32_t) pres_value_h << 16) | + ((int16_t) pres_value_l << 8) | + pres_value_xl; + + /* Add to entropy pool. */ + + add_sensor_randomness(pres_res); + + /* Convert to more usable format. */ + + pres->pressure_int_hP = pres_res / LPS25H_PRESSURE_INTERNAL_DIVIDER; + pres->pressure_Pa = (uint64_t)pres_res * 100000 / LPS25H_PRESSURE_INTERNAL_DIVIDER; + pres->raw_data = pres_res; + lps25h_dbg("Pressure: %u Pa\n", pres->pressure_Pa); + + return ret; +} + +static int lps25h_read_temper(FAR struct lps25h_dev_s *dev, + FAR lps25h_temper_data_t *temper) +{ + int ret; + uint8_t temper_addr_h = LPS25H_TEMP_OUT_H; + uint8_t temper_addr_l = LPS25H_TEMP_OUT_L; + uint8_t temper_value_h = 0; + uint8_t temper_value_l = 0; + int32_t temper_res; + int16_t raw_data; + + ret = lps25h_read_reg8(dev, &temper_addr_h, &temper_value_h); + if (ret < 0) + { + return ret; + } + + ret = lps25h_read_reg8(dev, &temper_addr_l, &temper_value_l); + if (ret < 0) + { + return ret; + } + + raw_data = (temper_value_h << 8) | temper_value_l; + + /* Add to entropy pool. */ + + add_sensor_randomness(raw_data); + + /* T(⁰C) = 42.5 + (raw / 480) + * => + * T(⁰C) * scale = (425 * 48 + raw) * scale / 480; + */ + + temper_res = (425 * 48 + raw_data); + temper_res *= LPS25H_TEMPER_DIVIDER; + temper_res /= 480; + + temper->int_temper = temper_res; + temper->raw_data = raw_data; + lps25h_dbg("Temperature: %d\n", temper_res); + + return ret; +} + +static int lps25h_who_am_i(struct lps25h_dev_s *dev, + lps25h_who_am_i_data * who_am_i_data) +{ + uint8_t who_addr = LPS25H_WHO_AM_I; + return lps25h_read_reg8(dev, &who_addr, &who_am_i_data->who_am_i); +} + +static int lps25h_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct lps25h_dev_s *dev = inode->i_private; + int ret = 0; + + while (sem_wait(&dev->devsem) != 0) + { + assert(errno == EINTR); + } + + switch (cmd) + { + case SNIOC_CFGR: + ret = lps25h_configure_dev(dev); + break; + + case SNIOC_PRESSURE_OUT: + ret = lps25h_read_pressure(dev, (lps25h_pressure_data_t *) arg); + break; + + case SNIOC_TEMPERATURE_OUT: + /* NOTE: call SNIOC_PRESSURE_OUT before this one, + * or results are bogus. + */ + + ret = lps25h_read_temper(dev, (lps25h_temper_data_t *) arg); + break; + + case SNIOC_SENSOR_OFF: + ret = lps25h_power_on_off(dev, false); + break; + + case SNIOC_GET_DEV_ID: + ret = lps25h_who_am_i(dev, (lps25h_who_am_i_data *) arg); + break; + + default: + ret = -EINVAL; + break; + } + + sem_post(&dev->devsem); + return ret; +} + +int lps25h_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR lps25h_config_t *config) +{ + int ret = 0; + FAR struct lps25h_dev_s *dev; + + dev = (struct lps25h_dev_s *)kmm_zalloc(sizeof(struct lps25h_dev_s)); + if (!dev) + { + lps25h_dbg("Memory cannot be allocated for LPS25H sensor\n"); + return -ENOMEM; + } + + sem_init(&dev->devsem, 0, 1); + sem_init(&dev->waitsem, 0, 0); + + dev->addr = addr; + dev->i2c = i2c; + dev->config = config; + + if (dev->config->irq_clear) + { + dev->config->irq_clear(dev->config); + } + + ret = register_driver(devpath, &g_lps25hops, 0666, dev); + + lps25h_dbg("Registered with %d\n", ret); + + if (ret < 0) + { + kmm_free(dev); + lps25h_dbg("Error occurred during the driver registering\n"); + return ERROR; + } + + dev->config->irq_attach(config, lps25h_int_handler, dev); + dev->config->irq_enable(config, false); + dev->irqenabled = false; + return OK; +} diff --git a/drivers/usbmisc/Kconfig b/drivers/usbmisc/Kconfig new file mode 100644 index 0000000000..68bd619ee3 --- /dev/null +++ b/drivers/usbmisc/Kconfig @@ -0,0 +1,29 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +comment "USB Miscellaneous drivers" + +config FUSB301 + bool "Fairchild FUSB301 USB type-C controller support" + default n + select I2C + ---help--- + Enable device driver for Fairchild USB type-C controller + +if FUSB301 + +config DEBUG_FUSB301 + bool "Enable debug support for the FUSB301" + default n + ---help--- + Enables debug support for the FUSB301 + +config FUSB301_NPOLLWAITERS + int "Number of waiters to poll" + default 2 + ---help--- + Maximum number of threads that can be waiting on poll() + +endif diff --git a/drivers/usbmisc/Make.defs b/drivers/usbmisc/Make.defs new file mode 100644 index 0000000000..fd9dd6af37 --- /dev/null +++ b/drivers/usbmisc/Make.defs @@ -0,0 +1,49 @@ +############################################################################ +# drivers/usbmisc/Make.defs +# +# Copyright (C) 2017 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +ifeq ($(CONFIG_USBMISC),y) + +# Include USB miscellaneous drivers + +ifeq ($(CONFIG_FUSB301),y) + CSRCS += fusb301.c +endif + +# Include USB miscellaneous build support + +DEPPATH += --dep-path usbmisc +VPATH += :usbmisc +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)usbmisc} +endif diff --git a/drivers/usbmisc/fusb301.c b/drivers/usbmisc/fusb301.c new file mode 100644 index 0000000000..c3627fd909 --- /dev/null +++ b/drivers/usbmisc/fusb301.c @@ -0,0 +1,855 @@ +/**************************************************************************** + * drivers/usbmisc/fusb301.c + * + * FUSB301 USB-C controller driver + * + * Copyright (C) 2016-2017 Haltian Ltd. All rights reserved. + * Authors: Harri Luhtala + * + * 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 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_FUSB301 +# define fusb301_err(x, ...) _err(x, ##__VA_ARGS__) +# define fusb301_info(x, ...) _info(x, ##__VA_ARGS__) +#else +# define fusb301_err(x, ...) uerr(x, ##__VA_ARGS__) +# define fusb301_info(x, ...) uinfo(x, ##__VA_ARGS__) +#endif + +/* Other macros */ + +#define FUSB301_I2C_RETRIES 10 + +/**************************************************************************** + * Private Data Types + ****************************************************************************/ + +struct fusb301_dev_s +{ + FAR struct i2c_master_s *i2c; /* I2C interface */ + uint8_t addr; /* I2C address */ + volatile bool int_pending; /* Interrupt received but handled */ + sem_t devsem; /* Manages exclusive access */ + FAR struct fusb301_config_s *config; /* Platform specific configuration */ +#ifndef CONFIG_DISABLE_POLL + FAR struct pollfd *fds[CONFIG_FUSB301_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Private Function prototypes + ****************************************************************************/ + +static int fusb301_open(FAR struct file *filep); +static int fusb301_close(FAR struct file *filep); +static ssize_t fusb301_read(FAR struct file *, FAR char *, size_t); +static ssize_t fusb301_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen); +static int fusb301_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int fusb301_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup); +static void fusb301_notify(FAR struct fusb301_dev_s *priv); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_fusb301ops = +{ + fusb301_open, /* open */ + fusb301_close, /* close */ + fusb301_read, /* read */ + fusb301_write, /* write */ + NULL, /* seek */ + fusb301_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , fusb301_poll /* poll */ +#endif +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + , NULL /* unlink */ + #endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fusb301_getreg + * + * Description: + * Read from an 8-bit FUSB301 register + * + * Input Parameters: + * priv - pointer to FUSB301 Private Structure + * reg - register to read + * + * Returned Value: + * Returns positive register value in case of success, otherwise ERROR + ****************************************************************************/ + +static int fusb301_getreg(FAR struct fusb301_dev_s *priv, uint8_t reg) +{ + int ret = -EIO; + int retries; + uint8_t regval; + struct i2c_msg_s msg[2]; + + DEBUGASSERT(priv); + + msg[0].addr = priv->addr; + msg[0].flags = 0; + msg[0].buffer = ® + msg[0].length = 1; + + msg[1].addr = priv->addr; + msg[1].flags = I2C_M_READ; + msg[1].buffer = ®val; + msg[1].length = 1; + + /* Perform the transfer */ + + for (retries = 0; retries < FUSB301_I2C_RETRIES; retries++) + { + ret = I2C_TRANSFER(priv->i2c, msg, 2); + if (ret == OK) + { + fusb301_info("reg:%02X, value:%02X\n", reg, regval); + return regval; + } + else + { + /* Some error. Try to reset I2C bus and keep trying. */ + +#ifdef CONFIG_I2C_RESET + if (retries == FUSB301_I2C_RETRIES - 1) + { + break; + } + + ret = up_i2creset(priv->i2c); + if (ret < 0) + { + fusb301_err("ERROR: up_i2creset failed: %d\n", ret); + return ret; + } +#endif + } + } + + fusb301_info("reg:%02X, error:%d\n", reg, ret); + return ret; +} + +/**************************************************************************** + * Name: fusb301_putreg + * + * Description: + * Write a value to an 8-bit FUSB301 register + * + * Input Parameters: + * priv - pointer to FUSB301 Private Structure + * regaddr - register to read + * regval - value to be written + * + * Returned Value: + * None + ****************************************************************************/ + +static int fusb301_putreg(FAR struct fusb301_dev_s *priv, uint8_t regaddr, + uint8_t regval) +{ + int ret = -EIO; + int retries; + struct i2c_msg_s msg; + uint8_t txbuffer[2]; + + /* Setup to the data to be transferred (register address and data). */ + + txbuffer[0] = regaddr; + txbuffer[1] = regval; + + /* Setup 8-bit FUSB301 address write message */ + + msg.addr = priv->addr; + msg.flags = 0; + msg.buffer = txbuffer; + msg.length = 2; + + /* Perform the transfer */ + + for (retries = 0; retries < FUSB301_I2C_RETRIES; retries++) + { + ret = I2C_TRANSFER(priv->i2c, &msg, 1); + if (ret == OK) + { + fusb301_info("reg:%02X, value:%02X\n", regaddr, regval); + + return OK; + } + else + { + /* Some error. Try to reset I2C bus and keep trying. */ + +#ifdef CONFIG_I2C_RESET + if (retries == FUSB301_I2C_RETRIES - 1) + { + break; + } + + ret = up_i2creset(priv->i2c); + if (ret < 0) + { + fusb301_err("ERROR: up_i2creset failed: %d\n", ret); + return ret; + } +#endif + } + } + + fusb301_err("ERROR: failed reg:%02X, value:%02X, error:%d\n", + regaddr, regval, ret); + return ret; +} + +/**************************************************************************** + * Name: fusb301_read_device_id + * + * Description: + * Read device version and revision IDs + * + ****************************************************************************/ + +static int fusb301_read_device_id(FAR struct fusb301_dev_s * priv, + FAR uint8_t * arg) +{ + int ret; + + ret = fusb301_getreg(priv, FUSB301_DEV_ID_REG); + if (ret < 0) + { + fusb301_err("ERROR: Failed to read device ID\n"); + return -EIO; + } + + *arg = ret; + return OK; +} + +/**************************************************************************** + * Name: fusb301_clear_interrupts + * + * Description: + * Clear interrupts from FUSB301 chip + * + ****************************************************************************/ + +static int fusb301_clear_interrupts(FAR struct fusb301_dev_s *priv) +{ + int ret = OK; + + ret = fusb301_getreg(priv, FUSB301_INTERRUPT_REG); + if (ret < 0) + { + fusb301_err("ERROR: Failed to clear interrupts\n"); + return -EIO; + } + + return ret; +} + +/**************************************************************************** + * Name: fusb301_setup + * + * Description: + * Setup FUSB301 chip + * + ****************************************************************************/ + +static int fusb301_setup(FAR struct fusb301_dev_s *priv, + struct fusb301_setup_s *setup) +{ + int ret = OK; + + fusb301_info("drp_tgl:%02X, host_curr:%02X, global_int:%X, mask:%02X\n", + setup->drp_toggle_timing, setup->host_current, setup->global_int_mask, + setup->int_mask); + + ret = fusb301_putreg(priv, FUSB301_CONTROL_REG, setup->drp_toggle_timing | + setup->host_current | setup->global_int_mask); + + if (ret < 0) + { + fusb301_err("ERROR: Failed to write control register\n"); + goto err_out; + } + + ret = fusb301_putreg(priv, FUSB301_MASK_REG, setup->int_mask); + if (ret < 0) + { + fusb301_err("ERROR: Failed to write mask register\n"); + } + +err_out: + return ret; +} + +/**************************************************************************** + * Name: fusb301_set_mode + * + * Description: + * Configure supported device modes (sink, source, DRP, accessory) + * + ****************************************************************************/ + +static int fusb301_set_mode(FAR struct fusb301_dev_s *priv, + enum fusb301_mode_e mode) +{ + int ret = OK; + + if (mode > MODE_DRP_ACC) + { + return -EINVAL; + } + + ret = fusb301_putreg(priv, FUSB301_MODE_REG, mode); + if (ret < 0) + { + fusb301_err("ERROR: Failed to write mode register\n"); + ret = -EIO; + } + + return ret; +} + +/**************************************************************************** + * Name: fusb301_set_state + * + * Description: + * Force device in specified state + * + ****************************************************************************/ + +static int fusb301_set_state(FAR struct fusb301_dev_s *priv, + enum fusb301_manual_e state) +{ + int ret = OK; + + if (state > MANUAL_UNATT_SNK) + { + return -EINVAL; + } + + ret = fusb301_putreg(priv, FUSB301_MANUAL_REG, state); + if (ret < 0) + { + fusb301_err("ERROR: Failed to write manual register\n"); + ret = -EIO; + } + + return ret; +} + +/**************************************************************************** + * Name: fusb301_read_status + * + * Description: + * Clear read status register + * + ****************************************************************************/ + +static int fusb301_read_status(FAR struct fusb301_dev_s *priv, + FAR uint8_t *arg) +{ + int ret; + + ret = fusb301_getreg(priv, FUSB301_STATUS_REG); + if (ret < 0) + { + fusb301_err("ERROR: Failed to read status\n"); + return -EIO; + } + + *arg = ret; + return OK; +} + +/**************************************************************************** + * Name: fusb301_read_devtype + * + * Description: + * Read type of attached device + * + ****************************************************************************/ + +static int fusb301_read_devtype(FAR struct fusb301_dev_s *priv, + FAR uint8_t *arg) +{ + int ret; + + ret = fusb301_getreg(priv, FUSB301_TYPE_REG); + if (ret < 0) + { + fusb301_err("ERROR: Failed to read type\n"); + return -EIO; + } + + *arg = ret; + return OK; +} + +/**************************************************************************** + * Name: fusb301_reset + * + * Description: + * Reset FUSB301 HW and clear I2C registers + * + ****************************************************************************/ + +static int fusb301_reset(FAR struct fusb301_dev_s *priv) +{ + int ret = OK; + + ret = fusb301_putreg(priv, FUSB301_RESET_REG, RESET_SW_RES); + if (ret < 0) + { + fusb301_err("ERROR: Failed to write reset register\n"); + ret = -EIO; + } + + return ret; +} + +/**************************************************************************** + * Name: fusb301_open + * + * Description: + * This function is called whenever the FUSB301 device is opened. + * + ****************************************************************************/ + +static int fusb301_open(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct fusb301_dev_s *priv = inode->i_private; + int ret = OK; + + /* Probe device */ + + ret = fusb301_getreg(priv, FUSB301_DEV_ID_REG); + if (ret < 0) + { + fusb301_err("ERROR: No response at given address 0x%02X\n", priv->addr); + ret = -EFAULT; + } + else + { + fusb301_info("device id: 0x%02X\n", ret); + + (void)fusb301_clear_interrupts(priv); + priv->config->irq_enable(priv->config, true); + } + + /* Error exit */ + + return ret; +} + +/**************************************************************************** + * Name: fusb301_close + * + * Description: + * This routine is called when the FUSB301 device is closed. + * + ****************************************************************************/ + +static int fusb301_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct fusb301_dev_s *priv = inode->i_private; + + priv->config->irq_enable(priv->config, false); + + return OK; +} + +/**************************************************************************** + * Name: fusb301_read + * Description: + * This routine is called when the FUSB301 device is read. + ****************************************************************************/ + +static ssize_t fusb301_read(FAR struct file *filep, FAR char *buffer, size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct fusb301_dev_s *priv = inode->i_private; + FAR struct fusb301_result_s *ptr; + irqstate_t flags; + int ret; + + if (buflen < sizeof(struct fusb301_result_s)) + { + return 0; + } + + ptr = (struct fusb301_result_s *)buffer; + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return -EINTR; + } + + flags = enter_critical_section(); + priv->int_pending = false; + leave_critical_section(flags); + + (void)fusb301_clear_interrupts(priv); + + ptr->status = fusb301_getreg(priv, FUSB301_STATUS_REG); + ptr->dev_type = fusb301_getreg(priv, FUSB301_TYPE_REG); + + sem_post(&priv->devsem); + return sizeof(struct fusb301_result_s); +} + +/**************************************************************************** + * Name: fusb301_write + * Description: + * This routine is called when the FUSB301 device is written to. + ****************************************************************************/ + +static ssize_t fusb301_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + ssize_t length = 0; + + return length; +} + +/**************************************************************************** + * Name: fusb301_ioctl + * Description: + * This routine is called when ioctl function call is performed for + * the FUSB301 device. + ****************************************************************************/ + +static int fusb301_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct fusb301_dev_s *priv = inode->i_private; + int ret; + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return -EINTR; + } + + fusb301_info("cmd: 0x%02X, arg:%lu\n", cmd, arg); + + switch (cmd) + { + case USBCIOC_READ_DEVID: + { + ret = fusb301_read_device_id(priv, (uint8_t *)arg); + } + break; + + case USBCIOC_SETUP: + { + ret = fusb301_setup(priv, (struct fusb301_setup_s *)arg); + } + break; + + case USBCIOC_SET_MODE: + { + ret = fusb301_set_mode(priv, (uint8_t)arg); + } + break; + + case USBCIOC_SET_STATE: + { + ret = fusb301_set_state(priv, (uint8_t)arg); + } + break; + + case USBCIOC_READ_STATUS: + { + ret = fusb301_read_status(priv, (uint8_t *)arg); + } + break; + + case USBCIOC_READ_DEVTYPE: + { + ret = fusb301_read_devtype(priv, (uint8_t *)arg); + } + break; + + case USBCIOC_RESET: + { + ret = fusb301_reset(priv); + } + break; + + default: + { + fusb301_err("ERROR: Unrecognized cmd: %d\n", cmd); + ret = -ENOTTY; + } + break; + } + + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: fusb301_poll + * Description: + * This routine is called during FUSB301 device poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int fusb301_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup) +{ + FAR struct inode *inode; + FAR struct fusb301_dev_s *priv; + irqstate_t flags; + int ret = OK; + int i; + + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct fusb301_dev_s *)inode->i_private; + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + return -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_FUSB301_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_FUSB301_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto out; + } + + flags = enter_critical_section(); + if (priv->int_pending) + { + fusb301_notify(priv); + } + + leave_critical_section(flags); + } + 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: + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: fusb301_notify + * + * Description: + * Notify thread about data to be available + * + ****************************************************************************/ + +static void fusb301_notify(FAR struct fusb301_dev_s *priv) +{ + DEBUGASSERT(priv != NULL); + + int i; + + /* If there are threads waiting on poll() for FUSB301 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_FUSB301_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + fusb301_info("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +} +#endif /* !CONFIG_DISABLE_POLL */ + +/**************************************************************************** + * Name: fusb301_callback + * + * Description: + * FUSB301 interrupt handler + * + ****************************************************************************/ + +static int fusb301_int_handler(int irq, FAR void *context, FAR void *arg) +{ + FAR struct fusb301_dev_s *priv = (FAR struct fusb301_dev_s *)arg; + irqstate_t flags; + + DEBUGASSERT(priv != NULL); + + flags = enter_critical_section(); + priv->int_pending = true; + +#ifndef CONFIG_DISABLE_POLL + fusb301_notify(priv); +#endif + leave_critical_section(flags); + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int fusb301_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR struct fusb301_config_s *config) +{ + FAR struct fusb301_dev_s *priv; + int ret; + + DEBUGASSERT(devpath != NULL && i2c != NULL && config != NULL); + + /* Initialize the FUSB301 device structure */ + + priv = (FAR struct fusb301_dev_s *)kmm_zalloc(sizeof(struct fusb301_dev_s)); + if (!priv) + { + fusb301_err("ERROR: Failed to allocate instance\n"); + return -ENOMEM; + } + + /* Initialize device structure semaphore */ + + sem_init(&priv->devsem, 0, 1); + + priv->int_pending = false; + priv->i2c = i2c; + priv->addr = addr; + priv->config = config; + + /* Register the character driver */ + + ret = register_driver(devpath, &g_fusb301ops, 0666, priv); + if (ret < 0) + { + fusb301_err("ERROR: Failed to register driver: %d\n", ret); + goto errout_with_priv; + } + + /* Prepare interrupt line and handler. */ + + priv->config->irq_clear(config); + priv->config->irq_attach(config, fusb301_int_handler, priv); + priv->config->irq_enable(config, false); + + return OK; + +errout_with_priv: + sem_destroy(&priv->devsem); + kmm_free(priv); + + return ret; +} diff --git a/include/nuttx/fs/ioctl.h b/include/nuttx/fs/ioctl.h index 4f6bab1aa1..e62cfc908f 100644 --- a/include/nuttx/fs/ioctl.h +++ b/include/nuttx/fs/ioctl.h @@ -86,8 +86,9 @@ #define _SPIBASE (0x2100) /* SPI driver commands */ #define _GPIOBASE (0x2200) /* GPIO driver commands */ #define _CLIOCBASE (0x2300) /* Contactless modules ioctl commands */ -#define _MAC802154BASE (0x2400) /* 802.15.4 MAC ioctl commands */ -#define _PHY802154BASE (0x2500) /* 802.15.4 Radio ioctl commands */ +#define _USBCBASE (0x2400) /* USB-C controller ioctl commands */ +#define _MAC802154BASE (0x2500) /* 802.15.4 MAC ioctl commands */ +#define _PHY802154BASE (0x2600) /* 802.15.4 Radio ioctl commands */ /* boardctl() commands share the same number space */ @@ -397,19 +398,25 @@ #define _GPIOCVALID(c) (_IOC_TYPE(c)==_GPIOBASE) #define _GPIOC(nr) _IOC(_GPIOBASE,nr) -/* Contactless driver ioctl definitions ****************************************/ +/* Contactless driver ioctl definitions *************************************/ /* (see nuttx/include/contactless/ioctl.h */ #define _CLIOCVALID(c) (_IOC_TYPE(c)==_CLIOCBASE) #define _CLIOC(nr) _IOC(_CLIOCBASE,nr) -/* 802.15.4 MAC driver ioctl definitions *******************************************/ +/* USB-C controller driver ioctl definitions ********************************/ +/* (see nuttx/include/usb/xxx.h */ + +#define _USBCIOCVALID(c) (_IOC_TYPE(c)==_USBCBASE) +#define _USBCIOC(nr) _IOC(_USBCBASE,nr) + +/* 802.15.4 MAC driver ioctl definitions ************************************/ /* (see nuttx/include/wireless/ieee802154/ieee802154_mac.h */ #define _MAC802154IOCVALID(c) (_IOC_TYPE(c)==_MAC802154BASE) #define _MAC802154IOC(nr) _IOC(_MAC802154BASE,nr) -/* 802.15.4 Radio driver ioctl definitions *******************************************/ +/* 802.15.4 Radio driver ioctl definitions **********************************/ /* (see nuttx/ieee802154/wireless/ieee802154_radio.h */ #define _PHY802154IOCVALID(c) (_IOC_TYPE(c)==_PHY802154BASE) diff --git a/include/nuttx/net/netconfig.h b/include/nuttx/net/netconfig.h index e00b75da91..3456132901 100644 --- a/include/nuttx/net/netconfig.h +++ b/include/nuttx/net/netconfig.h @@ -116,6 +116,22 @@ # endif #endif +#ifndef CONFIG_NET_6LOWPAN_FRAG +# undef CONFIG_NET_6LOWPAN_MTU +# undef CONFIG_NET_6LOWPAN_TCP_RECVWNDO +#endif + +#ifndef CONFIG_NET_6LOWPAN_MTU +# undef CONFIG_NET_6LOWPAN_TCP_RECVWNDO +# ifdef CONFIG_NET_6LOWPAN_FRAG +# define CONFIG_NET_6LOWPAN_MTU 1294 +# define CONFIG_NET_6LOWPAN_TCP_RECVWNDO 1220 +# else +# define CONFIG_NET_6LOWPAN_MTU CONFIG_NET_6LOWPAN_FRAMELEN +# define CONFIG_NET_6LOWPAN_TCP_RECVWNDO (CONFIG_NET_6LOWPAN_FRAMELEN - 25) +# endif +#endif + #if defined(CONFIG_NET_MULTILINK) /* We are supporting multiple network devices using different link layer * protocols. Get the size of the link layer header from the device @@ -142,15 +158,23 @@ # endif # ifdef CONFIG_NET_SLIP -# define _MIN_SLIP_MTU MIN(_MIN_LO_MTU,CONFIG_NET_SLIP_MTU) -# define _MAX_SLIP_MTU MAX(_MAX_LO_MTU,CONFIG_NET_SLIP_MTU) +# define _MIN_SLIP_MTU MIN(_MIN_LO_MTU,CONFIG_NET_6LOWPAN_MTU) +# define _MAX_SLIP_MTU MAX(_MAX_LO_MTU,CONFIG_NET_6LOWPAN_MTU) # else # define _MIN_SLIP_MTU _MIN_LO_MTU # define _MAX_SLIP_MTU _MAX_LO_MTU # endif -# define MIN_NET_DEV_MTU _MIN_SLIP_MTU -# define MAX_NET_DEV_MTU _MAX_SLIP_MTU +# ifdef CONFIG_NET_6LOWPAN +# define _MIN_6LOWPAN_MTU MIN(_MIN_LO_MTU,CONFIG_NET_SLIP_MTU) +# define _MAX_6LOWPAN_MTU MAX(_MAX_LO_MTU,CONFIG_NET_SLIP_MTU) +# else +# define _MIN_6LOWPAN_MTU _MIN_LO_MTU +# define _MAX_6LOWPAN_MTU _MAX_LO_MTU +# endif + +# define MIN_NET_DEV_MTU _MIN_6LOWPAN_MTU +# define MAX_NET_DEV_MTU _MAX_6LOWPAN_MTU /* For the loopback device, we will use the largest MTU */ @@ -190,8 +214,20 @@ # define MIN_NET_DEV_MTU NET_LO_MTU # define MAX_NET_DEV_MTU NET_LO_MTU +#elif defined(CONFIG_NET_6LOWPAN) + /* There is no link layer header with SLIP */ + +# ifndef CONFIG_NET_IPv6 +# error 6loWPAN requires IPv support +# endif + +# define NET_LL_HDRLEN(d) 0 +# define NET_DEV_MTU(d) CONFIG_NET_6LOWPAN_MTU +# define MIN_NET_DEV_MTU CONFIG_NET_6LOWPAN_MTU +# define MAX_NET_DEV_MTU CONFIG_NET_6LOWPAN_MTU + #else - /* Perhaps only Unix domain sockets of the loopback device */ + /* Perhaps only Unix domain sockets or the loopback device */ # define NET_LL_HDRLEN(d) 0 # define NET_DEV_MTU(d) 0 diff --git a/include/nuttx/net/sixlowpan.h b/include/nuttx/net/sixlowpan.h index be3bfa7636..7463763bff 100644 --- a/include/nuttx/net/sixlowpan.h +++ b/include/nuttx/net/sixlowpan.h @@ -340,9 +340,12 @@ struct rimeaddr_s * 5) On network input RX oprations, both buffers must be provided. The size * of the i_frame buffer is, again, greater than or equal to * CONFIG_NET_6LOWPAN_FRAMELEN. The larger dev.d_buf must have a size - * of at least . The dev.d_buf is used for de-compressing each - * frame and reassembling any fragmented packets to create the full input - * packet that is provided to the applicatino. + * of at least the advertised MTU of the protocol, CONFIG_NET_6LOWPAN_MTU. + * If fragmentation is enabled, then the logical packet size may be + * significantly larger than the size of the frame buffer. The dev.d_buf + * is used for de-compressing each frame and reassembling any fragmented + * packets to create the full input packet that is provided to the + * application. * * Frame Organization: * diff --git a/include/nuttx/sensors/hts221.h b/include/nuttx/sensors/hts221.h index 47142c3f82..1b9ddc5625 100644 --- a/include/nuttx/sensors/hts221.h +++ b/include/nuttx/sensors/hts221.h @@ -117,10 +117,11 @@ typedef struct hts221_settings_s typedef struct hts221_config_s { int irq; - CODE int (*irq_attach)(FAR struct hts221_config_s * state, xcpt_t isr); - CODE void (*irq_enable)(FAR const struct hts221_config_s * state, + CODE int (*irq_attach)(FAR struct hts221_config_s * state, xcpt_t isr, + FAR void *arg); + CODE void (*irq_enable)(FAR const struct hts221_config_s *state, bool enable); - CODE void (*irq_clear)(FAR const struct hts221_config_s * state); + CODE void (*irq_clear)(FAR const struct hts221_config_s *state); CODE int (*set_power)(FAR const struct hts221_config_s *state, bool on); } hts221_config_t; diff --git a/include/nuttx/sensors/ioctl.h b/include/nuttx/sensors/ioctl.h index 231c205601..3cef5a8997 100644 --- a/include/nuttx/sensors/ioctl.h +++ b/include/nuttx/sensors/ioctl.h @@ -125,4 +125,12 @@ #define SNIOC_READ_CONVERT_DATA _SNIOC(0x002f) #define SNIOC_DUMP_REGS _SNIOC(0x0030) +/* IOCTL commands unique to the LPS25H */ + +#define SNIOC_GET_DEV_ID _SNIOC(0x0031) +#define SNIOC_CFGR _SNIOC(0x0032) +#define SNIOC_TEMPERATURE_OUT _SNIOC(0x0033) +#define SNIOC_PRESSURE_OUT _SNIOC(0x0034) +#define SNIOC_SENSOR_OFF _SNIOC(0x0035) + #endif /* __INCLUDE_NUTTX_SENSORS_IOCTL_H */ diff --git a/include/nuttx/sensors/lps25h.h b/include/nuttx/sensors/lps25h.h new file mode 100644 index 0000000000..6f30d61cfc --- /dev/null +++ b/include/nuttx/sensors/lps25h.h @@ -0,0 +1,105 @@ +/**************************************************************************** + * include/nuttx/sensors/lps25h.h + * + * Copyright (C) 2014, 2017 Haltian Ltd. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor 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_NUTT_SENSORS_LPS25H_H +#define __INCLUDE_NUTT_SENSORS_LPS25H_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define LPS25H_TEMPER_DIVIDER 1000 + +#define LPS25H_VALID_WHO_AM_I 0xbd + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +typedef struct lps25h_temper_data_s +{ + int32_t int_temper; /* int_temper value must be divided by + * LPS25H_TEMPER_DIVIDER in your app code */ + int16_t raw_data; +} lps25h_temper_data_t; + +typedef struct lps25h_pressure_data_s +{ + uint32_t pressure_int_hP; + uint32_t pressure_Pa; + uint32_t raw_data; +} lps25h_pressure_data_t; + +typedef struct lps25h_who_am_i_data +{ + uint8_t who_am_i; +} lps25h_who_am_i_data; + +typedef struct lps25h_config_s +{ + /* Device characterization */ + + int irq; /* IRQ number received by interrupt handler. */ + + /* IRQ/GPIO access callbacks. These operations all hidden behind callbacks + * to isolate the driver from differences in GPIO interrupt handling + * by varying boards and MCUs. + * irq_attach - Attach the interrupt handler to the GPIO interrupt + * irq_enable - Enable or disable the GPIO + * irq_clear - Acknowledge/clear any pending GPIO interrupt + * set_power - Ask board to turn on regulator + */ + + CODE int (*irq_attach)(FAR struct lps25h_config_s *state, xcpt_t isr, + FAR void *arg); + CODE void (*irq_enable)(FAR const struct lps25h_config_s *state, + bool enable); + CODE void (*irq_clear)(FAR const struct lps25h_config_s *state); + CODE int (*set_power)(FAR const struct lps25h_config_s *state, bool on); +} lps25h_config_t; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +int lps25h_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR lps25h_config_t *config); + +#endif /* __INCLUDE_NUTT_SENSORS_LPS25H_H */ diff --git a/include/nuttx/usb/fusb301.h b/include/nuttx/usb/fusb301.h new file mode 100644 index 0000000000..deecff2b75 --- /dev/null +++ b/include/nuttx/usb/fusb301.h @@ -0,0 +1,243 @@ +/**************************************************************************** + * include/nuttx/usb/fusb301.h + * FUSB301 USB type-C controller driver + * + * Copyright (C) 2016-2017 Haltian Ltd. All rights reserved. + * Authors: Harri Luhtala + * + * 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_USB_FUSB301_H +#define __INCLUDE_NUTTX_USB_FUSB301_H + +#include + +/************************************************************************************ + * Pre-Processor Declarations + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* IOCTL Commands ***********************************************************/ + +#define USBCIOC_READ_DEVID _USBCIOC(0x0001) /* Arg: uint8_t* pointer */ +#define USBCIOC_SETUP _USBCIOC(0x0002) /* Arg: uint8_t* pointer */ +#define USBCIOC_SET_MODE _USBCIOC(0x0003) /* Arg: uint8_t value */ +#define USBCIOC_SET_STATE _USBCIOC(0x0004) /* Arg: uint8_t value */ +#define USBCIOC_READ_STATUS _USBCIOC(0x0005) /* Arg: uint8_t* pointer*/ +#define USBCIOC_READ_DEVTYPE _USBCIOC(0x0006) /* Arg: uint8_t* pointer*/ +#define USBCIOC_RESET _USBCIOC(0x0007) /* Arg: None */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +enum fusb301_reg_address_e +{ + FUSB301_DEV_ID_REG = 0x01, + FUSB301_MODE_REG, + FUSB301_CONTROL_REG, + FUSB301_MANUAL_REG, + FUSB301_RESET_REG, + FUSB301_MASK_REG = 0x10, + FUSB301_STATUS_REG, + FUSB301_TYPE_REG, + FUSB301_INTERRUPT_REG +}; + +/* Device ID - 0x01 */ + +enum fusb301_devid_mask_e +{ + DEV_ID_REVISION_MASK = 0x0F, + DEV_ID_VERSION_MASK = 0xF0 +}; + +#define DEV_ID_VER_A 0x10 +#define DEV_ID_REV_C 0x02 + +/* Modes - 0x02 */ + +enum fusb301_mode_e +{ + MODE_SRC = (1 << 0), + MODE_SRC_ACC = (1 << 1), + MODE_SNK = (1 << 2), + MODE_SNK_ACC = (1 << 3), + MODE_DRP = (1 << 4), + MODE_DRP_ACC = (1 << 5) +}; + +/* Control - 0x03 */ + +enum fusb301_control_e +{ + CONTROL_INT_ENABLE = (0 << 0), + CONTROL_INT_DISABLE = (1 << 0), + CONTROL_CUR_DISABLED = (0 << 1), + CONTROL_CUR_DEFAULT = (1 << 1), + CONTROL_CUR_1500 = (2 << 1), + CONTROL_CUR_3000 = (3 << 1), + CONTROL_TGL_35_15MS = (0 << 4), + CONTROL_TGL_30_20MS = (1 << 4), + CONTROL_TGL_25_25MS = (2 << 4), + CONTROL_TGL_20_30MS = (3 << 4) +}; + +/* Manual - 0x04 */ + +enum fusb301_manual_e +{ + MANUAL_ERROR_REC = (1 << 0), + MANUAL_DISABLED = (1 << 1), + MANUAL_UNATT_SRC = (1 << 2), + MANUAL_UNATT_SNK = (1 << 3) +}; + +/* Reset - 0x05 */ + +enum fusb301_reset_e +{ + RESET_SW_RES = (1 << 0) +}; + +/* Interrupt mask - 0x10 */ + +enum fusb301_int_mask_e +{ + INT_MASK_ATTACK = (1 << 0), + INT_MASK_DETACH = (1 << 1), + INT_MASK_BC_LVL = (1 << 2), + INT_MASK_ACC_CH = (1 << 3) +}; + +/* Status - 0x11 */ + +enum fusb301_status_e +{ + STATUS_ATTACH = (1 << 0), + STATUS_BC_SINK_UNATT = (0 << 1), + STATUS_BC_SINK_DEF = (1 << 1), + STATUS_BC_SINK_1500 = (2 << 1), + STATUS_BC_SINK_3000 = (3 << 1), + STATUS_VBUS_OK = (1 << 3), + STATUS_CC_NO_CONN = (0 << 4), + STATUS_CC_1 = (1 << 4), + STATUS_CC_2 = (2 << 4), + STATUS_CC_FAULT = (3 << 4) +}; + +/* Type - 0x12 */ + +enum fusb301_type_e +{ + TYPE_AUDIOACC = (1 << 0), + TYPE_DEBUGACC = (1 << 1), + TYPE_SOURCE = (1 << 3), + TYPE_SINK = (1 << 4) +}; + +/* Interrupt - 0x13 */ + +enum fusb301_interrupt_e +{ + INTERRUPT_ATTACH = (1 << 0), + INTERRUPT_DETACH = (1 << 1), + INTERRUPT_BC_LVL = (1 << 2), + INTERRUPT_ACC_CH = (1 << 3) +}; + +struct fusb301_result_s +{ + uint8_t status; + uint8_t dev_type; +}; + +struct fusb301_setup_s +{ + uint8_t drp_toggle_timing; + uint8_t host_current; + uint8_t int_mask; + bool global_int_mask; +}; + +struct fusb301_config_s +{ + /* Device characterization */ + + int irq; + + CODE int (*irq_attach)(FAR struct fusb301_config_s *state, xcpt_t isr, + FAR void *arg); + CODE void (*irq_enable)(FAR struct fusb301_config_s *state, bool enable); + CODE void (*irq_clear)(FAR struct fusb301_config_s *state); +}; + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/**************************************************************************** + * Name: fusb301_register + * + * Description: + * Register the FUSB301 character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/usbc0" + * i2c - An instance of the I2C interface to use to communicate with FUSB301 + * addr - The I2C address of the FUSB301. The I2C address of the FUSB301 is 0x25. + * config - Pointer to FUSB301 configuration + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int fusb301_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr, FAR struct fusb301_config_s *config); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __INCLUDE_NUTTX_USB_FUSB301_H */ diff --git a/net/netdev/netdev_register.c b/net/netdev/netdev_register.c index 4dda608c1a..737d51195b 100644 --- a/net/netdev/netdev_register.c +++ b/net/netdev/netdev_register.c @@ -229,8 +229,8 @@ int netdev_register(FAR struct net_driver_s *dev, enum net_lltype_e lltype) #ifdef CONFIG_NET_6LOWPAN case NET_LL_IEEE802154: /* IEEE 802.15.4 MAC */ - dev->d_llhdrlen = 0; /* REVISIT */ - dev->d_mtu = CONFIG_NET_6LOWPAN_FRAMELEN; + dev->d_llhdrlen = 0; + dev->d_mtu = CONFIG_NET_6LOWPAN_MTU; #ifdef CONFIG_NET_TCP dev->d_recvwndo = CONFIG_NET_6LOWPAN_TCP_RECVWNDO; #endif diff --git a/net/sixlowpan/Kconfig b/net/sixlowpan/Kconfig index bbbdeb1b13..406a5e8d34 100644 --- a/net/sixlowpan/Kconfig +++ b/net/sixlowpan/Kconfig @@ -159,15 +159,32 @@ config NET_6LOWPAN_MAXPAYLOAD of a 802.15.4 frame) - 25 bytes (for the 802.15.4 MAClayer header). This can be increased for systems with larger packet sizes. +config NET_6LOWPAN_MTU + int "6LoWPAN packet buffer size" + default 1294 + range 590 1518 + depends on NET_6LOWPAN_FRAG + ---help--- + Packet buffer size. This size includes the TCP/UDP payload plus the + size of TCP/UDP header, the IP header, and the Ethernet header. + This value is normally referred to as the MTU (Maximum Transmission + Unit); the payload is the MSS (Maximum Segment Size). + + NOTE that this option depends on fragmentation support. By + supporting fragmentation, we can handle quite large "logical" packet + sizes. Without fragmentation support, the MTU is equal to the frame + size and that has already been selected. + config NET_6LOWPAN_TCP_RECVWNDO int "6LoWPAN TCP receive window size" - default 102 + default 1220 if NET_6LOWPAN_FRAG + default 102 if !NET_6LOWPAN_FRAG depends on NET_TCP ---help--- The size of the advertised receiver's window. Should be set low - (i.e., to the size of the IEEE802.15.4 frame payload) if the application - is slow to process incoming data, or high (32768 bytes) if the - application processes data quickly. REVISIT! + (i.e., to the size of the IEEE802.15.4 MTU or frame payload) if + the application is slow to process incoming data, or high (32768 + bytes) if the application processes data quickly. config NET_6LOWPAN_SNIFFER default n diff --git a/net/sixlowpan/sixlowpan_send.c b/net/sixlowpan/sixlowpan_send.c index 9a7b0095cd..ad72cce383 100644 --- a/net/sixlowpan/sixlowpan_send.c +++ b/net/sixlowpan/sixlowpan_send.c @@ -54,6 +54,7 @@ #include #include +#include "nuttx/net/iob.h" #include "nuttx/net/netdev.h" #include "nuttx/net/ip.h" #include "nuttx/net/tcp.h" @@ -61,6 +62,7 @@ #include "nuttx/net/icmpv6.h" #include "nuttx/net/sixlowpan.h" +#include "iob/iob.h" #include "netdev/netdev.h" #include "socket/socket.h" #include "tcp/tcp.h" @@ -69,6 +71,26 @@ #ifdef CONFIG_NET_6LOWPAN +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* A single IOB must be big enough to hold a full frame */ + +#if CONFIG_IOB_BUFSIZE < CONFIG_NET_6LOWPAN_FRAMELEN +# error IOBs must be large enough to hold full IEEE802.14.5 frame +#endif + +/* There must be at least enough IOBs to hold the full MTU. Probably still + * won't work unless there are a few more. + */ + +#if CONFIG_NET_6LOWPAN_MTU > (CONFIG_IOB_BUFSIZE * CONFIG_IOB_NBUFFERS) +# error Not enough IOBs to hold one full IEEE802.14.5 packet +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -177,14 +199,15 @@ static void sixlowpan_compress_ipv6hdr(FAR struct ieee802154_driver_s *ieee, * * Input Parameters: * ieee - Pointer to IEEE802.15.4 MAC driver structure. - * ipv6 - Pointer to the IPv6 header to "compress" + * iobq - The list of frames to send. * * Returned Value: - * None + * Zero (OK) on success; otherwise a negated errno value is returned. * ****************************************************************************/ -static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee) +static int sixlowpan_send_frame(FAR struct ieee802154_driver_s *ieee, + FAR struct iob_s *iobq) { /* Prepare the frame */ #warning Missing logic @@ -247,10 +270,10 @@ int sixlowpan_send(FAR struct net_driver_s *dev, size_t len, FAR const struct rimeaddr_s *raddr) { FAR struct ieee802154_driver_s *ieee = (FAR struct ieee802154_driver_s *)dev; - - int framer_hdrlen; /* Framer header length */ - struct rimeaddr_s dest; /* The MAC address of the destination of the packet */ - uint16_t outlen = 0; /* Number of bytes processed. */ + FAR struct iob_s *iob; + int framer_hdrlen; + struct rimeaddr_s dest; + uint16_t outlen = 0; /* Initialize device-specific data */ @@ -356,7 +379,7 @@ int sixlowpan_send(FAR struct net_driver_s *dev, if (framer_hdrlen < 0) { /* Failed to determine the size of the header failed. */ - + nerr("ERROR: sixlowpan_framecreate() failed: %d\n", framer_hdrlen); return framer_hdrlen; } @@ -368,6 +391,13 @@ int sixlowpan_send(FAR struct net_driver_s *dev, (int)ieee->i_rime_hdrlen) { #if CONFIG_NET_6LOWPAN_FRAG + /* qhead will hold the generated frames; Subsequent frames will be + * added at qtail. + */ + + FAR struct iob_s *qhead; + FAR struct iob_s *qtail; + /* The outbound IPv6 packet is too large to fit into a single 15.4 * packet, so we fragment it into multiple packets and send them. * The first fragment contains frag1 dispatch, then @@ -377,6 +407,11 @@ int sixlowpan_send(FAR struct net_driver_s *dev, ninfo("Fragmentation sending packet len %d\n", len); + /* Allocate an IOB to hold the first fragment, waiting if necessary. */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + /* Create 1st Fragment */ # warning Missing logic @@ -390,13 +425,19 @@ int sixlowpan_send(FAR struct net_driver_s *dev, /* Copy payload and send */ # warning Missing logic - + /* Check TX result. */ # warning Missing logic /* Set outlen to what we already sent from the IP payload */ # warning Missing logic + /* Add the first frame to the IOB queue */ + + qhead = iob; + qtail = iob; + iob->io_flink = NULL; + /* Create following fragments * Datagram tag is already in the buffer, we need to set the * FRAGN dispatch and for each fragment, the offset @@ -405,20 +446,31 @@ int sixlowpan_send(FAR struct net_driver_s *dev, while (outlen < len) { - /* Copy payload and send */ + /* Allocate an IOB to hold the next fragment, waiting if + * necessary. + */ + + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + /* Copy payload */ # warning Missing logic ninfo("sixlowpan output: fragment offset %d, len %d, tag %d\n", outlen >> 3, g_rime_payloadlen, g_mytag); -# warning Missing logic - sixlowpan_send_frame(ieee); + /* Add the next frame to the tail of the IOB queue */ + + qtail->io_flink = iob; + iob->io_flink = NULL; /* Check tx result. */ # warning Missing logic } - return -ENOSYS; + /* Send the list of frames */ + + return sixlowpan_send_frame(ieee, qhead); #else nerr("ERROR: Packet too large: %d\n", len); nerr(" Cannot to be sent without fragmentation support\n"); @@ -433,10 +485,19 @@ int sixlowpan_send(FAR struct net_driver_s *dev, * and send in one frame. */ - return sixlowpan_send_frame(ieee); - } + /* Allocate an IOB to hold the frame, waiting if necessary. */ - return -ENOSYS; + iob = iob_alloc(false); + DEBUGASSERT(iob != NULL); + + /* Format the single frame */ +# warning Missing logic + + /* Send the single frame */ + + iob->io_flink = NULL; + return sixlowpan_send_frame(ieee, iob); + } } #endif /* CONFIG_NET_6LOWPAN */